From ff426d83549bb100dd8f2dab029a017f707af1bf Mon Sep 17 00:00:00 2001 From: Mirko Denecke Date: Mon, 20 May 2024 20:09:44 +0200 Subject: [PATCH 01/15] AP_Bootloader: Reserve ID range for UAV-DEV GmbH --- Tools/AP_Bootloader/board_types.txt | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 2e8c4c44736599..94e195d31dac7a 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -316,6 +316,15 @@ AP_HW_AIRVOLUTE_DCS2 5200 AP_HW_AOCODA-RC-H743DUAL 5210 AP_HW_AOCODA-RC-F405V3 5211 +# IDs 5220-5239 reserved for UAV-DEV GmbH +AP_HW_UAV-DEV-HAT-H7 5220 +AP_HW_UAV-DEV-NucPilot-H7 5221 +AP_HW_UAV-DEV-M10S-L4 5222 +AP_HW_UAV-DEV-F9P-G4 5223 +AP_HW_UAV-DEV-UM982-G4 5224 +AP_HW_UAV-DEV-M20D-G4 5225 +AP_HW_UAV-DEV-Sensorboard-G4 5226 + #IDs 5301-5399 reserved for Sierra Aerospace AP_HW_Sierra-TrueNavPro-G4 5301 AP_HW_Sierra-TrueNavIC 5302 From 5fd4e23fa9e8f22ca0bf64659192ee6eb77d2f3b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 22 May 2024 08:47:52 +1000 Subject: [PATCH 02/15] AP_Compass: removed IST8310 overrun message this is not useful and just causes concern to users. Any small bus delay can trigger this. We have health monitoring at a higher level --- libraries/AP_Compass/AP_Compass_IST8308.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_IST8308.cpp b/libraries/AP_Compass/AP_Compass_IST8308.cpp index c4c3ea499feecb..49adf9de7b1c99 100644 --- a/libraries/AP_Compass/AP_Compass_IST8308.cpp +++ b/libraries/AP_Compass/AP_Compass_IST8308.cpp @@ -200,10 +200,6 @@ void AP_Compass_IST8308::timer() return; } - if (stat & STAT1_VAL_DOR) { - printf("IST8308: data overrun\n"); - } - if (!_dev->read_registers(DATAX_L_REG, (uint8_t *) &buffer, sizeof(buffer))) { return; From a5e11911fc13e90d858c3a3c237bc5e4e726cb49 Mon Sep 17 00:00:00 2001 From: James O'Shannessy <12959316+joshanne@users.noreply.github.com> Date: Tue, 21 May 2024 09:32:22 +1000 Subject: [PATCH 03/15] AP_Mount: Only save converted mount if mount was previously set in the first place The mount library force configures the mount type on conversion, even if the mount was never configured in the first place --- libraries/AP_Mount/AP_Mount.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 70a136283d5968..f93b277406f448 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -1015,7 +1015,10 @@ void AP_Mount::convert_params() // convert MNT_TYPE to MNT1_TYPE int8_t mnt_type = 0; IGNORE_RETURN(AP_Param::get_param_by_index(this, 19, AP_PARAM_INT8, &mnt_type)); - if (mnt_type > 0) { + if (mnt_type == 0) { + // if the mount was not previously set, no need to perform the upgrade logic + return; + } else if (mnt_type > 0) { int8_t stab_roll = 0; int8_t stab_pitch = 0; IGNORE_RETURN(AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &stab_roll)); @@ -1025,8 +1028,9 @@ void AP_Mount::convert_params() // conversion is still done even if HAL_MOUNT_SERVO_ENABLED is false mnt_type = 7; // (int8_t)Type::BrushlessPWM; } + // if the mount was previously set, then we need to save the upgraded mount type + _params[0].type.set_and_save(mnt_type); } - _params[0].type.set_and_save(mnt_type); // convert MNT_JSTICK_SPD to MNT1_RC_RATE int8_t jstick_spd = 0; From 9112b14414e266686f38a3612808a83ece1cab22 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 24 Apr 2024 16:51:46 +0100 Subject: [PATCH 04/15] AP_RCProtocol: add frame ids for CRSF baro/vario --- libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h index aaaf0fb2bf2d8f..e4ebba502775e5 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h @@ -80,7 +80,9 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { enum FrameType { CRSF_FRAMETYPE_GPS = 0x02, + CRSF_FRAMETYPE_VARIO = 0x07, CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08, + CRSF_FRAMETYPE_BARO_VARIO = 0x09, CRSF_FRAMETYPE_HEARTBEAT = 0x0B, CRSF_FRAMETYPE_VTX = 0x0F, CRSF_FRAMETYPE_VTX_TELEM = 0x10, From 1e2621466c8e6ec0e2803d4f409b6600d5cc95af Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 27 Apr 2024 14:58:54 +0100 Subject: [PATCH 05/15] AP_Frsky_Telem: factor out vspeed and nav alt --- libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp | 37 ++----------------- .../AP_Frsky_SPort_Passthrough.cpp | 2 +- 2 files changed, 4 insertions(+), 35 deletions(-) diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp index 9db8f890c3ad70..e78b576c27c45f 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp @@ -5,6 +5,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -44,47 +45,15 @@ void AP_Frsky_Backend::loop(void) } } -/* - * get vertical speed from ahrs, if not available fall back to baro climbrate, units is m/s - * for FrSky D and SPort protocols - */ -float AP_Frsky_Backend::get_vspeed_ms(void) -{ - - { - // release semaphore as soon as possible - AP_AHRS &_ahrs = AP::ahrs(); - Vector3f v; - WITH_SEMAPHORE(_ahrs.get_semaphore()); - if (_ahrs.get_velocity_NED(v)) { - return -v.z; - } - } - - auto &_baro = AP::baro(); - WITH_SEMAPHORE(_baro.get_semaphore()); - return _baro.get_climb_rate(); -} - /* * prepare altitude between vehicle and home location data * for FrSky D and SPort protocols */ void AP_Frsky_Backend::calc_nav_alt(void) { - _SPort_data.vario_vspd = (int32_t)(get_vspeed_ms()*100); //convert to cm/s - - Location loc; - float current_height = 0; - - AP_AHRS &_ahrs = AP::ahrs(); - WITH_SEMAPHORE(_ahrs.get_semaphore()); - if (_ahrs.get_location(loc)) { - if (!loc.get_alt_m(Location::AltFrame::ABSOLUTE, current_height)) { - // ignore this error - } - } + _SPort_data.vario_vspd = (int32_t)(AP_RCTelemetry::get_vspeed_ms()*100); //convert to cm/s + float current_height = AP_RCTelemetry::get_nav_alt_m(); _SPort_data.alt_nav_meters = float_to_uint16(current_height); _SPort_data.alt_nav_cm = float_to_uint16((current_height - _SPort_data.alt_nav_meters) * 100); } diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp index 2f3acb0fb36277..db60fa40483bb0 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp @@ -646,7 +646,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_home(void) */ uint32_t AP_Frsky_SPort_Passthrough::calc_velandyaw(void) { - float vspd = get_vspeed_ms(); + float vspd = AP_RCTelemetry::get_vspeed_ms(); // vertical velocity in dm/s uint32_t velandyaw = prep_number(roundf(vspd * 10), 2, 1); float airspeed_m; // m/s From 3a4fdb16a8afd15048ae66845fa1b9a39d2c950b Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 24 Apr 2024 16:52:13 +0100 Subject: [PATCH 06/15] AP_RCTelemetry: add support for baro/vario CRSF frames --- libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp | 69 +++++++++++++++++++++ libraries/AP_RCTelemetry/AP_CRSF_Telem.h | 17 +++++ libraries/AP_RCTelemetry/AP_RCTelemetry.cpp | 44 +++++++++++++ libraries/AP_RCTelemetry/AP_RCTelemetry.h | 4 ++ 4 files changed, 134 insertions(+) diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index c645add90fcba7..4f76626701f56c 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -81,6 +81,7 @@ void AP_CRSF_Telem::setup_wfq_scheduler(void) // CRSF telemetry rate is 150Hz (4ms) max, so these rates must fit add_scheduler_entry(50, 100); // heartbeat 10Hz add_scheduler_entry(5, 20); // parameters 50Hz (generally not active unless requested by the TX) + add_scheduler_entry(50, 200); // baro_vario 5Hz add_scheduler_entry(50, 120); // Attitude and compass 8Hz add_scheduler_entry(200, 1000); // VTX parameters 1Hz add_scheduler_entry(1300, 500); // battery 2Hz @@ -152,6 +153,8 @@ void AP_CRSF_Telem::update_custom_telemetry_rates(AP_RCProtocol_CRSF::RFMode rf_ // standard telemetry for high data rates set_scheduler_entry(BATTERY, 1000, 1000); // 1Hz set_scheduler_entry(ATTITUDE, 1000, 1000); // 1Hz + set_scheduler_entry(BARO_VARIO, 1000, 1000); // 1Hz + set_scheduler_entry(VARIO, 1000, 1000); // 1Hz // custom telemetry for high data rates set_scheduler_entry(GPS, 550, 500); // 2.0Hz set_scheduler_entry(PASSTHROUGH, 100, 100); // 8Hz @@ -160,6 +163,8 @@ void AP_CRSF_Telem::update_custom_telemetry_rates(AP_RCProtocol_CRSF::RFMode rf_ // standard telemetry for low data rates set_scheduler_entry(BATTERY, 1000, 2000); // 0.5Hz set_scheduler_entry(ATTITUDE, 1000, 3000); // 0.33Hz + set_scheduler_entry(BARO_VARIO, 1000, 3000); // 0.33Hz + set_scheduler_entry(VARIO, 1000, 3000); // 0.33Hz if (is_elrs()) { // ELRS custom telemetry for low data rates set_scheduler_entry(GPS, 550, 1000); // 1.0Hz @@ -320,6 +325,8 @@ void AP_CRSF_Telem::queue_message(MAV_SEVERITY severity, const char *text) void AP_CRSF_Telem::disable_tx_entries() { disable_scheduler_entry(ATTITUDE); + disable_scheduler_entry(BARO_VARIO); + disable_scheduler_entry(VARIO); disable_scheduler_entry(BATTERY); disable_scheduler_entry(GPS); disable_scheduler_entry(FLIGHT_MODE); @@ -334,6 +341,8 @@ void AP_CRSF_Telem::disable_tx_entries() void AP_CRSF_Telem::enable_tx_entries() { enable_scheduler_entry(ATTITUDE); + enable_scheduler_entry(BARO_VARIO); + enable_scheduler_entry(VARIO); enable_scheduler_entry(BATTERY); enable_scheduler_entry(GPS); enable_scheduler_entry(FLIGHT_MODE); @@ -428,6 +437,12 @@ void AP_CRSF_Telem::process_packet(uint8_t idx) case PARAMETERS: // update parameter settings process_pending_requests(); break; + case BARO_VARIO: + calc_baro_vario(); + break; + case VARIO: + calc_vario(); + break; case ATTITUDE: calc_attitude(); break; @@ -914,6 +929,60 @@ void AP_CRSF_Telem::calc_battery() _telem_pending = true; } +uint16_t AP_CRSF_Telem::get_altitude_packed() +{ + int32_t altitude_dm = get_nav_alt_m(Location::AltFrame::ABOVE_HOME) * 10; + + enum : int32_t { + ALT_MIN_DM = 10000, // minimum altitude in dm + ALT_THRESHOLD_DM = 0x8000 - ALT_MIN_DM, // altitude of precision changing in dm + ALT_MAX_DM = 0x7ffe * 10 - 5, // maximum altitude in dm + }; + + if (altitude_dm < -ALT_MIN_DM) { // less than minimum altitude + return 0; // minimum + } + if (altitude_dm > ALT_MAX_DM) { // more than maximum + return 0xFFFEU; // maximum + } + if(altitude_dm < ALT_THRESHOLD_DM) { //dm-resolution range + return uint16_t(altitude_dm + ALT_MIN_DM); + } + return uint16_t((altitude_dm + 5) / 10) | uint16_t(0x8000); // meter-resolution range +} + +int8_t AP_CRSF_Telem::get_vertical_speed_packed() +{ + float vspeed = get_vspeed_ms(); + float vertical_speed_cm_s = vspeed * 100.0f; + const int16_t Kl = 100; // linearity constant; + const float Kr = .026f; // range constant; + int8_t vspeed_packed = int8_t(logf(fabsf(vertical_speed_cm_s)/Kl + 1)/Kr); + return vspeed_packed * (is_negative(vertical_speed_cm_s) ? -1 : 1); +} + +// prepare vario data +void AP_CRSF_Telem::calc_baro_vario() +{ + _telem.bcast.baro_vario.altitude_packed = get_altitude_packed(); + _telem.bcast.baro_vario.vertical_speed_packed = get_vertical_speed_packed(); + + _telem_size = sizeof(BaroVarioFrame); + _telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_BARO_VARIO; + + _telem_pending = true; +} + +// prepare vario data +void AP_CRSF_Telem::calc_vario() +{ + _telem.bcast.vario.v_speed = int16_t(get_vspeed_ms() * 100.0f); + _telem_size = sizeof(VarioFrame); + _telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_VARIO; + + _telem_pending = true; +} + // prepare gps data void AP_CRSF_Telem::calc_gps() { diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h index e0d557cb74cc79..f02e531a5759e4 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h @@ -64,6 +64,15 @@ class AP_CRSF_Telem : public AP_RCTelemetry { uint8_t remaining; // ( percent ) }; + struct PACKED BaroVarioFrame { + uint16_t altitude_packed; // Altitude above start (calibration) point. + int8_t vertical_speed_packed; // vertical speed. + }; + + struct PACKED VarioFrame { + int16_t v_speed; // vertical speed cm/s + }; + struct PACKED VTXFrame { #if __BYTE_ORDER != __LITTLE_ENDIAN #error "Only supported on little-endian architectures" @@ -201,6 +210,8 @@ class AP_CRSF_Telem : public AP_RCTelemetry { union PACKED BroadcastFrame { GPSFrame gps; HeartbeatFrame heartbeat; + BaroVarioFrame baro_vario; + VarioFrame vario; BatteryFrame battery; VTXFrame vtx; AttitudeFrame attitude; @@ -244,6 +255,8 @@ class AP_CRSF_Telem : public AP_RCTelemetry { enum SensorType { HEARTBEAT, PARAMETERS, + BARO_VARIO, + VARIO, ATTITUDE, VTX_PARAMETERS, BATTERY, @@ -267,6 +280,10 @@ class AP_CRSF_Telem : public AP_RCTelemetry { void calc_parameter_ping(); void calc_heartbeat(); void calc_battery(); + uint16_t get_altitude_packed(); + int8_t get_vertical_speed_packed(); + void calc_baro_vario(); + void calc_vario(); void calc_gps(); void calc_attitude(); void calc_flight_mode(); diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp index c57c3d35cefe17..3c7d4e3358e73e 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #ifdef TELEM_DEBUG # define debug(fmt, args...) hal.console->printf("Telem: " fmt "\n", ##args) @@ -293,3 +294,46 @@ uint32_t AP_RCTelemetry::sensor_status_flags() const return ~health & enabled & present; } + +/* + * get vertical speed from ahrs, if not available fall back to baro climbrate, units is m/s + */ +float AP_RCTelemetry::get_vspeed_ms(void) +{ + { + // release semaphore as soon as possible + AP_AHRS &_ahrs = AP::ahrs(); + Vector3f v; + WITH_SEMAPHORE(_ahrs.get_semaphore()); + if (_ahrs.get_velocity_NED(v)) { + return -v.z; + } + } + auto &_baro = AP::baro(); + WITH_SEMAPHORE(_baro.get_semaphore()); + return _baro.get_climb_rate(); +} + +/* + * prepare altitude between vehicle and home location data + */ +float AP_RCTelemetry::get_nav_alt_m(Location::AltFrame frame) +{ + Location loc; + float current_height = 0; + + AP_AHRS &_ahrs = AP::ahrs(); + WITH_SEMAPHORE(_ahrs.get_semaphore()); + + if (frame == Location::AltFrame::ABOVE_HOME) { + _ahrs.get_relative_position_D_home(current_height); + return -current_height; + } + + if (_ahrs.get_location(loc)) { + if (!loc.get_alt_m(frame, current_height)) { + // ignore this error + } + } + return current_height; +} diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.h b/libraries/AP_RCTelemetry/AP_RCTelemetry.h index 40fc27ca838b25..5ebea0ff35770e 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.h +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.h @@ -18,6 +18,7 @@ #include #include #include +#include #define TELEM_PAYLOAD_STATUS_CAPACITY 5 // size of the message buffer queue (max number of messages waiting to be sent) @@ -77,6 +78,9 @@ class AP_RCTelemetry { return _scheduler.max_packet_rate; } + static float get_vspeed_ms(void); + static float get_nav_alt_m(Location::AltFrame frame = Location::AltFrame::ABSOLUTE); + protected: uint8_t run_wfq_scheduler(const bool use_shaper = true); // process a specific entry From 1e777390b26641ad70b6922941df7723c7ec89db Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 22 May 2024 10:12:22 +0900 Subject: [PATCH 07/15] AP_Mount: add Backend_Serial --- .../AP_Mount/AP_Mount_Backend_Serial.cpp | 24 ++++++++++ libraries/AP_Mount/AP_Mount_Backend_Serial.h | 48 +++++++++++++++++++ 2 files changed, 72 insertions(+) create mode 100644 libraries/AP_Mount/AP_Mount_Backend_Serial.cpp create mode 100644 libraries/AP_Mount/AP_Mount_Backend_Serial.h diff --git a/libraries/AP_Mount/AP_Mount_Backend_Serial.cpp b/libraries/AP_Mount/AP_Mount_Backend_Serial.cpp new file mode 100644 index 00000000000000..ec270510575652 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Backend_Serial.cpp @@ -0,0 +1,24 @@ +#include "AP_Mount_Backend_Serial.h" + +#if HAL_MOUNT_ENABLED +#include + +// Default init function for every mount +void AP_Mount_Backend_Serial::init() +{ + const AP_SerialManager& serial_manager = AP::serialmanager(); + + // search for serial port. hild classes should check that uart is not nullptr + _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, _serial_instance); + if (_uart == nullptr) { + return; + } + + // initialised successfully if uart is found + _initialised = true; + + // call the parent class init + AP_Mount_Backend::init(); +} + +#endif // HAL_MOUNT_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Backend_Serial.h b/libraries/AP_Mount/AP_Mount_Backend_Serial.h new file mode 100644 index 00000000000000..49fd2a50bdeb75 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Backend_Serial.h @@ -0,0 +1,48 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + Mount driver backend class for serial drivers + Mounts using custom serial protocols should be derived from this class + */ +#pragma once + +#include "AP_Mount_config.h" + +#if HAL_MOUNT_ENABLED + +#include "AP_Mount_Backend.h" + +class AP_Mount_Backend_Serial : public AP_Mount_Backend +{ +public: + // Constructor + AP_Mount_Backend_Serial(class AP_Mount &frontend, class AP_Mount_Params ¶ms, uint8_t instance, uint8_t serial_instance) : + AP_Mount_Backend(frontend, params, instance), + _serial_instance(serial_instance) + {} + + // perform any required initialisation for this instance + void init() override; + +protected: + + // internal variables + AP_HAL::UARTDriver *_uart; // uart connected to gimbal + uint8_t _serial_instance; // this instance's serial instance number + bool _initialised; // true if uart has been initialised +}; + +#endif // HAL_MOUNT_ENABLED From 790b5e85659851c227e4252a8879661087b5ebac Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 22 May 2024 10:13:27 +0900 Subject: [PATCH 08/15] AP_Mount: Siyi inherits from serial backend --- libraries/AP_Mount/AP_Mount_Siyi.cpp | 15 --------------- libraries/AP_Mount/AP_Mount_Siyi.h | 11 +++-------- 2 files changed, 3 insertions(+), 23 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 3f00d1caa03e3a..77704637dc99c4 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -5,7 +5,6 @@ #include #include #include -#include #include extern const AP_HAL::HAL& hal; @@ -32,20 +31,6 @@ const AP_Mount_Siyi::HWInfo AP_Mount_Siyi::hardware_lookup_table[] { {{'7','A'}, "ZT30"}, }; -// init - performs any required initialisation for this instance -void AP_Mount_Siyi::init() -{ - const AP_SerialManager& serial_manager = AP::serialmanager(); - - _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0); - if (_uart == nullptr) { - return; - } - - _initialised = true; - AP_Mount_Backend::init(); -} - // update mount position - should be called periodically void AP_Mount_Siyi::update() { diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index 75a03efda3271d..c6366e6b29d044 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -19,7 +19,7 @@ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_Backend_Serial.h" #if HAL_MOUNT_SIYI_ENABLED @@ -29,19 +29,16 @@ #define AP_MOUNT_SIYI_PACKETLEN_MAX 38 // maximum number of bytes in a packet sent to or received from the gimbal -class AP_Mount_Siyi : public AP_Mount_Backend +class AP_Mount_Siyi : public AP_Mount_Backend_Serial { public: // Constructor - using AP_Mount_Backend::AP_Mount_Backend; + using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial; /* Do not allow copies */ CLASS_NO_COPY(AP_Mount_Siyi); - // init - performs any required initialisation for this instance - void init() override; - // update mount position - should be called periodically void update() override; @@ -293,8 +290,6 @@ class AP_Mount_Siyi : public AP_Mount_Backend void check_firmware_version() const; // internal variables - AP_HAL::UARTDriver *_uart; // uart connected to gimbal - bool _initialised; // true once the driver has been initialised bool _got_hardware_id; // true once hardware id ha been received FirmwareVersion _fw_version; // firmware version (for reporting for GCS) From 7fc00efe7e5c1aa6214802dad9a2b8c87cc4d5dd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 22 May 2024 12:41:01 +0900 Subject: [PATCH 09/15] AP_Mount: Viewpro inherits from serial backend --- libraries/AP_Mount/AP_Mount_Viewpro.cpp | 15 --------------- libraries/AP_Mount/AP_Mount_Viewpro.h | 11 +++-------- 2 files changed, 3 insertions(+), 23 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index 409d9cc27b4e8a..e04510962ef07d 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -7,7 +7,6 @@ #include #include #include -#include extern const AP_HAL::HAL& hal; @@ -28,20 +27,6 @@ extern const AP_HAL::HAL& hal; const char* AP_Mount_Viewpro::send_text_prefix = "Viewpro:"; -// init - performs any required initialisation for this instance -void AP_Mount_Viewpro::init() -{ - const AP_SerialManager& serial_manager = AP::serialmanager(); - - _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0); - if (_uart == nullptr) { - return; - } - - _initialised = true; - AP_Mount_Backend::init(); -} - // update mount position - should be called periodically void AP_Mount_Viewpro::update() { diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.h b/libraries/AP_Mount/AP_Mount_Viewpro.h index 1ddaa283212be4..1e045c8fd1ae29 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.h +++ b/libraries/AP_Mount/AP_Mount_Viewpro.h @@ -16,7 +16,7 @@ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_Backend_Serial.h" #if HAL_MOUNT_VIEWPRO_ENABLED @@ -27,19 +27,16 @@ #define AP_MOUNT_VIEWPRO_PACKETLEN_MAX 63 // maximum number of bytes in a packet sent to or received from the gimbal -class AP_Mount_Viewpro : public AP_Mount_Backend +class AP_Mount_Viewpro : public AP_Mount_Backend_Serial { public: // Constructor - using AP_Mount_Backend::AP_Mount_Backend; + using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial; /* Do not allow copies */ CLASS_NO_COPY(AP_Mount_Viewpro); - // init - performs any required initialisation for this instance - void init() override; - // update mount position - should be called periodically void update() override; @@ -378,8 +375,6 @@ class AP_Mount_Viewpro : public AP_Mount_Backend bool send_m_ahrs(); // internal variables - AP_HAL::UARTDriver *_uart; // uart connected to gimbal - bool _initialised; // true once the driver has been initialised uint8_t _msg_buff[AP_MOUNT_VIEWPRO_PACKETLEN_MAX]; // buffer holding latest bytes from gimbal uint8_t _msg_buff_len; // number of bytes held in msg buff const uint8_t _msg_buff_data_start = 2; // data starts at this byte of _msg_buff From 99626b73ff0867d05e5bc246ed52e7ae2df45280 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 22 May 2024 12:41:17 +0900 Subject: [PATCH 10/15] AP_Mount: SToRM32_serial inherits from serial backend --- .../AP_Mount/AP_Mount_SToRM32_serial.cpp | 28 +++++-------------- libraries/AP_Mount/AP_Mount_SToRM32_serial.h | 13 ++------- 2 files changed, 10 insertions(+), 31 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 928a40a297496b..82387a0e93ec15 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -4,20 +4,6 @@ #include #include #include -#include - -// init - performs any required initialisation for this instance -void AP_Mount_SToRM32_serial::init() -{ - const AP_SerialManager& serial_manager = AP::serialmanager(); - - _port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0); - if (_port) { - _initialised = true; - } - AP_Mount_Backend::init(); - -} // update mount position - should be called periodically void AP_Mount_SToRM32_serial::update() @@ -142,7 +128,7 @@ bool AP_Mount_SToRM32_serial::can_send(bool with_control) { if (with_control) { required_tx += sizeof(AP_Mount_SToRM32_serial::cmd_set_angles_struct); } - return (_reply_type == ReplyType_UNKNOWN) && (_port->txspace() >= required_tx); + return (_reply_type == ReplyType_UNKNOWN) && (_uart->txspace() >= required_tx); } @@ -167,7 +153,7 @@ void AP_Mount_SToRM32_serial::send_target_angles(const MountTarget& angle_target return; } - if ((size_t)_port->txspace() < sizeof(cmd_set_angles_data)) { + if ((size_t)_uart->txspace() < sizeof(cmd_set_angles_data)) { return; } @@ -181,7 +167,7 @@ void AP_Mount_SToRM32_serial::send_target_angles(const MountTarget& angle_target cmd_set_angles_data.crc = crc_calculate(&buf[1], sizeof(cmd_set_angles_data)-3); for (uint8_t i = 0; i != sizeof(cmd_set_angles_data) ; i++) { - _port->write(buf[i]); + _uart->write(buf[i]); } // store time of send @@ -194,11 +180,11 @@ void AP_Mount_SToRM32_serial::get_angles() { return; } - if (_port->txspace() < 1) { + if (_uart->txspace() < 1) { return; } - _port->write('d'); + _uart->write('d'); }; @@ -220,14 +206,14 @@ void AP_Mount_SToRM32_serial::read_incoming() { uint8_t data; int16_t numc; - numc = _port->available(); + numc = _uart->available(); if (numc < 0 ) { return; } for (int16_t i = 0; i < numc; i++) { // Process bytes received - data = _port->read(); + data = _uart->read(); if (_reply_type == ReplyType_UNKNOWN) { continue; } diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index e6632ca10eb8bc..895143e80bb72a 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -3,7 +3,7 @@ */ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_Backend_Serial.h" #if HAL_MOUNT_STORM32SERIAL_ENABLED @@ -13,15 +13,12 @@ #define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second -class AP_Mount_SToRM32_serial : public AP_Mount_Backend +class AP_Mount_SToRM32_serial : public AP_Mount_Backend_Serial { public: // Constructor - using AP_Mount_Backend::AP_Mount_Backend; - - // init - performs any required initialisation for this instance - void init() override; + using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial; // update mount position - should be called periodically void update() override; @@ -127,11 +124,7 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend // internal variables - AP_HAL::UARTDriver *_port; - - bool _initialised; // true once the driver has been initialised uint32_t _last_send; // system time of last do_mount_control sent to gimbal - uint8_t _reply_length; uint8_t _reply_counter; ReplyType _reply_type = ReplyType_UNKNOWN; From 72b5efd8b361ea4f46840de7a95d903362f19631 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 22 May 2024 12:41:57 +0900 Subject: [PATCH 11/15] AP_Mount: serial backends gets instance --- libraries/AP_Mount/AP_Mount.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index f93b277406f448..a9de1354b774e2 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -62,6 +62,9 @@ void AP_Mount::init() // primary is reset to the first instantiated mount bool primary_set = false; + // keep track of number of serial instances for initialisation + uint8_t serial_instance = 0; + // create each instance for (uint8_t instance=0; instance Date: Tue, 21 May 2024 14:09:27 +1000 Subject: [PATCH 12/15] hwdef: fold minimal_GPS.inc into sole user --- libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat | 5 ++--- libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc | 7 ------- 2 files changed, 2 insertions(+), 10 deletions(-) delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat index f00cbdfd420dd0..f63913f67a500d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat @@ -98,9 +98,8 @@ define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 define HAL_PERIPH_GPS_PORT_DEFAULT 0 - -# minimal GPS drivers to reduce flash usage -include ../include/minimal_GPS.inc +define AP_GPS_BACKEND_DEFAULT_ENABLED 0 +define AP_GPS_UBLOX_ENABLED 1 # GPS PPS PA15 GPS_PPS_IN INPUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc deleted file mode 100644 index cd519bdd32839b..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc +++ /dev/null @@ -1,7 +0,0 @@ -# include file to reduce flash by including less GPS drivers - -define AP_GPS_BACKEND_DEFAULT_ENABLED 0 -define AP_GPS_UBLOX_ENABLED 1 -define AP_GPS_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS -undef HAL_MSP_GPS_ENABLED -define HAL_MSP_GPS_ENABLED HAL_MSP_SENSORS_ENABLED From 766d92faa6a2c65b05975da0f27d10a1714e8dda Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 21 May 2024 17:57:15 +1000 Subject: [PATCH 13/15] autotest: add test for Copter behaviour in guided with force-arm --- Tools/autotest/arducopter.py | 41 ++++++++++++++++++++++++++++++++---- 1 file changed, 37 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 7e5e3de3748439..610c3bb963259d 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -4599,10 +4599,7 @@ def fly_guided_stop(self, m.climb < climb_tolerance): break - def fly_guided_move_global_relative_alt(self, lat, lon, alt): - startpos = self.mav.recv_match(type='GLOBAL_POSITION_INT', - blocking=True) - + def send_set_position_target_global_int(self, lat, lon, alt): self.mav.mav.set_position_target_global_int_send( 0, # timestamp 1, # target system_id @@ -4622,6 +4619,12 @@ def fly_guided_move_global_relative_alt(self, lat, lon, alt): 0, # yawrate ) + def fly_guided_move_global_relative_alt(self, lat, lon, alt): + startpos = self.mav.recv_match(type='GLOBAL_POSITION_INT', + blocking=True) + + self.send_set_position_target_global_int(lat, lon, alt) + tstart = self.get_sim_time() while True: if self.get_sim_time_cached() - tstart > 200: @@ -11345,6 +11348,35 @@ def check_altitude(mav, m): self.context_pop() self.reboot_sitl(force=True) + def GuidedForceArm(self): + '''ensure Guided acts appropriately when force-armed''' + self.set_parameters({ + "EK3_SRC2_VELXY": 5, + "SIM_GPS_DISABLE": 1, + }) + self.load_default_params_file("copter-optflow.parm") + self.reboot_sitl() + self.delay_sim_time(30) + self.change_mode('GUIDED') + self.arm_vehicle(force=True) + self.takeoff(20, mode='GUIDED') + location = self.offset_location_ne(self.sim_location(), metres_north=0, metres_east=-300) + self.progress("Ensure we don't move for 10 seconds") + tstart = self.get_sim_time() + startpos = self.sim_location_int() + while True: + now = self.get_sim_time_cached() + if now - tstart > 10: + break + self.send_set_position_target_global_int(int(location.lat*1e7), int(location.lng*1e7), 10) + dist = self.get_distance_int(startpos, self.sim_location_int()) + if dist > 10: + raise NotAchievedException("Wandered too far from start position") + self.delay_sim_time(1) + + self.disarm_vehicle(force=True) + self.reboot_sitl() + def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ @@ -11431,6 +11463,7 @@ def tests2b(self): # this block currently around 9.5mins here self.AutoRTL, self.EK3_OGN_HGT_MASK, self.FarOrigin, + self.GuidedForceArm, ]) return ret From fcebd0c8c2f13fd6cb1aa397fea7d94245851277 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 21 May 2024 18:48:15 +1000 Subject: [PATCH 14/15] Copter: avoid Guided submode change unless can change Loc to Vec-from-origin ordering problem between changing the submode and setting a valid position --- ArduCopter/mode_guided.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index d590b1125403dc..3065d9b9a68aa9 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -456,6 +456,13 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y return true; } + // set position target and zero velocity and acceleration + Vector3f pos_target_f; + bool terrain_alt; + if (!wp_nav->get_vector_NEU(dest_loc, pos_target_f, terrain_alt)) { + return false; + } + // if configured to use position controller for position control // ensure we are in position control mode if (guided_mode != SubMode::Pos) { @@ -465,13 +472,6 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y // set yaw state set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); - // set position target and zero velocity and acceleration - Vector3f pos_target_f; - bool terrain_alt; - if (!wp_nav->get_vector_NEU(dest_loc, pos_target_f, terrain_alt)) { - return false; - } - // initialise terrain following if needed if (terrain_alt) { // get current alt above terrain From 0c6f3964382a77ee375623cca029df7d4cd966fd Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 7 May 2024 03:55:00 +0100 Subject: [PATCH 15/15] AP_Scripting: docs: document all functions currently documented on the wiki --- libraries/AP_Scripting/docs/docs.lua | 783 ++++++++++++++------------- 1 file changed, 401 insertions(+), 382 deletions(-) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 47781807f4cd76..6aa389f0cd5498 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -710,143 +710,149 @@ function Parameter_ud:init_by_info(key, group_element, type) end function Parameter_ud:init(name) end --- desc +-- Vector2f is a userdata object that holds a 2D vector with x and y components. The components are stored as floating point numbers. +-- To create a new Vector2f you can call Vector2f() to allocate a new one, or call a method that returns one to you. ---@class (exact) Vector2f_ud ---@operator add(Vector2f_ud): Vector2f_ud ---@operator sub(Vector2f_ud): Vector2f_ud local Vector2f_ud = {} +-- Create Vector2f object ---@return Vector2f_ud function Vector2f() end --- copy ----@return Vector2f_ud +-- Copy this Vector2f returning a new userdata object +---@return Vector2f_ud -- a copy of this Vector2f function Vector2f_ud:copy() end --- get field +-- get y component ---@return number function Vector2f_ud:y() end --- set field +-- set y component ---@param value number function Vector2f_ud:y(value) end --- get field +-- get x component ---@return number function Vector2f_ud:x() end --- set field +-- set x component ---@param value number function Vector2f_ud:x(value) end --- desc ----@param angle_rad number +-- rotate vector by angle in radians +---@param angle_rad number -- angle in radians function Vector2f_ud:rotate(angle_rad) end --- desc ----@return boolean +-- Check if both components of the vector are zero +---@return boolean -- true if both components are zero function Vector2f_ud:is_zero() end --- desc ----@return boolean +-- Check if either components of the vector are infinite +---@return boolean -- true if either components are infinite function Vector2f_ud:is_inf() end --- desc ----@return boolean +-- Check if either components of the vector are nan +---@return boolean -- true if either components are nan function Vector2f_ud:is_nan() end --- desc +-- normalize this vector to a unit length function Vector2f_ud:normalize() end --- desc ----@return number +-- Calculate length of this vector sqrt(x^2 + y^2) +---@return number -- length of this vector function Vector2f_ud:length() end --- desc ----@return number +-- Calculate the angle of this vector in radians +-- 2PI + atan2(-x, y) +---@return number -- angle in radians function Vector2f_ud:angle() end --- desc +-- Vector3f is a userdata object that holds a 3D vector with x, y and z components. +-- The components are stored as floating point numbers. +-- To create a new Vector3f you can call Vector3f() to allocate a new one, or call a method that returns one to you. ---@class (exact) Vector3f_ud ---@operator add(Vector3f_ud): Vector3f_ud ---@operator sub(Vector3f_ud): Vector3f_ud local Vector3f_ud = {} +-- Create Vector3f object ---@return Vector3f_ud function Vector3f() end --- copy ----@return Vector3f_ud +-- Copy this Vector3f returning a new userdata object +---@return Vector3f_ud -- a copy of this Vector3f function Vector3f_ud:copy() end --- get field +-- get z component ---@return number function Vector3f_ud:z() end --- set field +-- set z component ---@param value number function Vector3f_ud:z(value) end --- get field +-- get y component ---@return number function Vector3f_ud:y() end --- set field +-- set y component ---@param value number function Vector3f_ud:y(value) end --- get field +-- get x component ---@return number function Vector3f_ud:x() end --- set field +-- set x component ---@param value number function Vector3f_ud:x(value) end --- desc +-- Return a new Vector3 based on this one with scaled length and the same changing direction ---@param scale_factor number ----@return Vector3f_ud +---@return Vector3f_ud -- scaled copy of this vector function Vector3f_ud:scale(scale_factor) end --- desc +-- Cross product of two Vector3fs ---@param vector Vector3f_ud ----@return Vector3f_ud +---@return Vector3f_ud -- result function Vector3f_ud:cross(vector) end --- desc +-- Dot product of two Vector3fs ---@param vector Vector3f_ud ----@return number +---@return number -- result function Vector3f_ud:dot(vector) end --- desc ----@return boolean +-- Check if all components of the vector are zero +---@return boolean -- true if all components are zero function Vector3f_ud:is_zero() end --- desc ----@return boolean +-- Check if any components of the vector are infinite +---@return boolean -- true if any components are infinite function Vector3f_ud:is_inf() end --- desc ----@return boolean +-- Check if any components of the vector are nan +---@return boolean -- true if any components are nan function Vector3f_ud:is_nan() end --- desc +-- normalize this vector to a unit length function Vector3f_ud:normalize() end --- desc ----@return number +-- Calculate length of this vector sqrt(x^2 + y^2 + z^2) +---@return number -- length of this vector function Vector3f_ud:length() end -- Computes angle between this vector and vector v2 ----@param v2 Vector3f_ud +---@param v2 Vector3f_ud ---@return number function Vector3f_ud:angle(v2) end --- desc +-- Rotate vector by angle in radians in xy plane leaving z untouched ---@param param1 number -- XY rotation in radians function Vector3f_ud:rotate_xy(param1) end --- desc +-- return the x and y components of this vector as a Vector2f ---@return Vector2f_ud function Vector3f_ud:xy() end @@ -937,83 +943,86 @@ function Quaternion_ud:normalize() end ---@return number function Quaternion_ud:length() end --- desc +-- Location is a userdata object that holds locations expressed as latitude, longitude, altitude. +-- The altitude can be in several different frames, relative to home, absolute altitude above mean sea level, or relative to terrain. +-- To create a new Location userdata you can call Location() to allocate an empty location object, or call a method that returns one to you. ---@class (exact) Location_ud local Location_ud = {} +-- Create location object ---@return Location_ud function Location() end --- copy ----@return Location_ud +-- Copy this location returning a new userdata object +---@return Location_ud -- a copy of this location function Location_ud:copy() end --- get field ----@return boolean +-- get loiter xtrack +---@return boolean -- Get if the location is used for a loiter location this flags if the aircraft should track from the center point, or from the exit location of the loiter. function Location_ud:loiter_xtrack() end --- set field ----@param value boolean +-- set loiter xtrack +---@param value boolean -- Set if the location is used for a loiter location this flags if the aircraft should track from the center point, or from the exit location of the loiter. function Location_ud:loiter_xtrack(value) end --- get field ----@return boolean +-- get origin alt +---@return boolean -- true if altitude is relative to origin function Location_ud:origin_alt() end --- set field ----@param value boolean +-- set origin alt +---@param value boolean -- set true if altitude is relative to origin function Location_ud:origin_alt(value) end --- get field ----@return boolean +-- get terrain alt +---@return boolean -- true if altitude is relative to terrain function Location_ud:terrain_alt() end --- set field ----@param value boolean +-- set terrain alt +---@param value boolean -- set true if altitude is relative to home function Location_ud:terrain_alt(value) end --- get field ----@return boolean +-- get relative alt +---@return boolean -- true if altitude is relative to home function Location_ud:relative_alt() end --- set field ----@param value boolean +-- set relative alt +---@param value boolean -- set true if altitude is relative to home function Location_ud:relative_alt(value) end --- get field ----@return integer +-- get altitude in cm +---@return integer -- altitude in cm function Location_ud:alt() end --- set field +-- set altitude in cm ---@param value integer function Location_ud:alt(value) end --- get field ----@return integer +-- get longitude in degrees * 1e7 +---@return integer -- longitude in degrees * 1e7 function Location_ud:lng() end --- set field ----@param value integer +-- set longitude in degrees * 1e7 +---@param value integer -- longitude in degrees * 1e7 function Location_ud:lng(value) end --- get field ----@return integer +-- get latitude in degrees * 1e7 +---@return integer -- latitude in degrees * 1e7 function Location_ud:lat() end --- set field ----@param value integer +-- set latitude in degrees * 1e7 +---@param value integer -- latitude in degrees * 1e7 function Location_ud:lat(value) end --- get altitude frame ----@return integer +-- get altitude frame of this location +---@return integer -- altitude frame ---| '0' # ABSOLUTE ---| '1' # ABOVE_HOME ---| '2' # ABOVE_ORIGIN ---| '3' # ABOVE_TERRAIN function Location_ud:get_alt_frame() end --- desc ----@param desired_frame integer +-- Set the altitude frame of this location +---@param desired_frame integer -- altitude frame ---| '0' # ABSOLUTE ---| '1' # ABOVE_HOME ---| '2' # ABOVE_ORIGIN @@ -1021,44 +1030,45 @@ function Location_ud:get_alt_frame() end ---@return boolean function Location_ud:change_alt_frame(desired_frame) end --- desc ----@param loc Location_ud ----@return Vector2f_ud +-- Given a Location this calculates the north and east distance between the two locations in meters. +---@param loc Location_ud -- location to compare with +---@return Vector2f_ud -- North east distance vector in meters function Location_ud:get_distance_NE(loc) end --- desc ----@param loc Location_ud ----@return Vector3f_ud +-- Given a Location this calculates the north, east and down distance between the two locations in meters. +---@param loc Location_ud -- location to compare with +---@return Vector3f_ud -- North east down distance vector in meters function Location_ud:get_distance_NED(loc) end --- desc ----@param loc Location_ud ----@return number +-- Given a Location this calculates the relative bearing to the location in radians +---@param loc Location_ud -- location to compare with +---@return number -- bearing in radians function Location_ud:get_bearing(loc) end --- desc ----@return Vector3f_ud|nil +-- Returns the offset from the EKF origin to this location. +-- Returns nil if the EKF origin wasn’t available at the time this was called. +---@return Vector3f_ud|nil -- Vector between origin and location north east up in meters function Location_ud:get_vector_from_origin_NEU() end --- desc ----@param bearing_deg number ----@param distance number +-- Translates this Location by the specified distance given a bearing. +---@param bearing_deg number -- bearing in degrees +---@param distance number -- distance in meters function Location_ud:offset_bearing(bearing_deg, distance) end --- desc ----@param bearing_deg number ----@param pitch_deg number ----@param distance number +-- Translates this Location by the specified distance given a bearing and pitch. +---@param bearing_deg number -- bearing in degrees +---@param pitch_deg number -- pitch in degrees +---@param distance number -- distance in meters function Location_ud:offset_bearing_and_pitch(bearing_deg, pitch_deg, distance) end --- desc ----@param ofs_north number ----@param ofs_east number +-- Translates this Location by the specified north and east distance in meters. +---@param ofs_north number -- north offset in meters +---@param ofs_east number -- east offset in meters function Location_ud:offset(ofs_north, ofs_east) end --- desc ----@param loc Location_ud ----@return number +-- Given a Location this calculates the horizontal distance between the two locations in meters. +---@param loc Location_ud -- location to compare with +---@return number -- horizontal distance in meters function Location_ud:get_distance(loc) end -- desc @@ -1141,31 +1151,31 @@ function AP_HAL__I2CDevice_ud:write_register(register_num, value) end function AP_HAL__I2CDevice_ud:set_retries(retries) end --- desc +-- Serial driver object ---@class (exact) AP_HAL__UARTDriver_ud local AP_HAL__UARTDriver_ud = {} --- desc +-- Set flow control option for serial port ---@param flow_control_setting integer ---| '0' # disabled ---| '1' # enabled ---| '2' # auto function AP_HAL__UARTDriver_ud:set_flow_control(flow_control_setting) end --- desc +-- Returns number of available bytes to read. ---@return uint32_t_ud function AP_HAL__UARTDriver_ud:available() end --- desc ----@param value integer ----@return uint32_t_ud +-- Writes a single byte +---@param value integer -- byte to write +---@return uint32_t_ud -- 1 if success else 0 function AP_HAL__UARTDriver_ud:write(value) end --- desc ----@return integer +-- Read a single byte from the serial port +---@return integer -- byte, -1 if not available function AP_HAL__UARTDriver_ud:read() end --- desc +-- Start serial port with given baud rate ---@param baud_rate uint32_t_ud|integer|number function AP_HAL__UARTDriver_ud:begin(baud_rate) end @@ -1739,21 +1749,21 @@ LED = {} function LED:get_rgb() end --- desc +-- button handling button = {} --- desc ----@param button_number integer +-- Returns button state if available. Buttons are 1 indexed. +---@param button_number integer -- button number 1 indexed. ---@return boolean function button:get_button_state(button_number) end --- desc +-- RPM handling RPM = {} --- desc ----@param instance integer ----@return number|nil +-- Returns RPM of given instance, or nil if not available +---@param instance integer -- RPM instance +---@return number|nil -- RPM value if available function RPM:get_rpm(instance) end @@ -1846,30 +1856,30 @@ function mission:jump_to_landing_sequence() end ---@return boolean function mission:jump_to_abort_landing_sequence() end --- desc +-- Parameter access param = {} --- desc ----@param name string ----@param value number ----@return boolean +-- set and save parameter value, this will be saved for subsequent boots +---@param name string -- parameter name +---@param value number -- value to set and save +---@return boolean -- true if parameter was found function param:set_and_save(name, value) end --- desc ----@param name string ----@param value number ----@return boolean +-- set parameter value, this will not be retained over a reboot +---@param name string -- parameter name +---@param value number -- value to set +---@return boolean -- true if parameter was found function param:set(name, value) end --- desc ----@param name string ----@return number|nil +-- Get parameter value +---@param name string -- parameter name +---@return number|nil -- nill if parameter was not found function param:get(name) end --- desc ----@param name string ----@param value number ----@return boolean +-- Set default value for a given parameter. If the parameter has not been configured by the user then the set to this default value. +---@param name string -- parameter name +---@param value number -- default value +---@return boolean -- true if parameter was found function param:set_default(name, value) end -- desc @@ -1918,54 +1928,54 @@ function ESCTelemetryData_ud:temperature_cdeg(value) end esc_telem = {} -- update telemetry data for an ESC instance ----@param instance integer -- 0 is first motor +---@param instance integer -- esc instance 0 indexed ---@param telemdata ESCTelemetryData_ud ---@param data_mask integer -- bit mask of what fields are filled in function esc_telem:update_telem_data(instance, telemdata, data_mask) end --- desc ----@param instance integer ----@return uint32_t_ud|nil +-- Returns an individual ESC’s usage time in seconds, or nil if not available. +---@param instance integer -- esc instance 0 indexed +---@return uint32_t_ud|nil -- usage time in seconds, nill if not available. function esc_telem:get_usage_seconds(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return number|nil function esc_telem:get_consumption_mah(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return number|nil function esc_telem:get_voltage(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return number|nil function esc_telem:get_current(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return integer|nil function esc_telem:get_motor_temperature(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return integer|nil function esc_telem:get_temperature(instance) end -- desc ----@param instance integer +---@param instance integer -- esc instance 0 indexed ---@return number|nil function esc_telem:get_rpm(instance) end -- update RPM for an ESC ----@param esc_index integer -- ESC number +---@param esc_index integer -- esc instance 0 indexed ---@param rpm integer -- RPM ---@param error_rate number -- error rate function esc_telem:update_rpm(esc_index, rpm, error_rate) end -- set scale factor for RPM on a motor ----@param esc_index integer -- index (0 is first motor) +---@param esc_index integer -- esc instance 0 indexed ---@param scale_factor number -- factor function esc_telem:set_rpm_scale(esc_index, scale_factor) end @@ -1988,16 +1998,16 @@ function optical_flow:enabled() end -- desc baro = {} --- desc ----@return number +-- get external temperature in degrees C +---@return number -- temperature in degrees C function baro:get_external_temperature() end --- temperature in degrees C ----@return number +-- get temperature in degrees C +---@return number -- temperature in degrees C function baro:get_temperature() end --- pressure in Pascal. Divide by 100 for millibars or hectopascals ----@return number +-- Returns pressure in Pascal. Divide by 100 for millibars or hectopascals +---@return number -- pressure in Pascal function baro:get_pressure() end -- get current altitude in meters relative to altitude at the time @@ -2011,7 +2021,7 @@ function baro:get_altitude() end function baro:healthy(instance) end --- desc +-- Serial ports serial = {} -- Returns the UART instance that allows connections from scripts (those with SERIALx_PROTOCOL = 28`). @@ -2053,9 +2063,9 @@ function rc:run_aux_function(aux_fun, ch_flag) end ---@return RC_Channel_ud|nil function rc:find_channel_for_option(aux_fun) end --- desc ----@param chan_num integer ----@return integer|nil +-- Returns the RC input PWM value given a channel number. Note that channel here is indexed from 1. Returns nill if channel is not available. +---@param chan_num integer -- input channel number, 1 indexed +---@return integer|nil -- pwm input or nil if not availables function rc:get_pwm(chan_num) end @@ -2075,90 +2085,90 @@ function SRV_Channels:get_emergency_stop() end function SRV_Channels:get_safety_state() end -- desc ----@param function_num integer +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) ---@param range integer function SRV_Channels:set_range(function_num, range) end -- desc ----@param function_num integer +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) ---@param angle integer function SRV_Channels:set_angle(function_num, angle) end -- desc ----@param function_num integer +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) ---@param value number function SRV_Channels:set_output_norm(function_num, value) end --- desc ----@param function_num integer ----@return number +-- Get the scaled value for a given servo function +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) +---@return number -- scaled value function SRV_Channels:get_output_scaled(function_num) end --- desc ----@param function_num integer ----@return integer|nil +-- Returns first servo output PWM value an output assigned output_function (See SERVOx_FUNCTION parameters). Nil if none is assigned. +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) +---@return integer|nil -- output pwm if available function SRV_Channels:get_output_pwm(function_num) end --- desc ----@param function_num integer ----@param value number +-- Set the scaled value of the output function, scale is out of the value set with the set_range or set_angle call +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) +---@param value number -- scaled value function SRV_Channels:set_output_scaled(function_num, value) end --- desc ----@param chan integer ----@param pwm integer ----@param timeout_ms integer +-- Sets servo channel to specified PWM for a time in ms. This overrides any commands from the autopilot until the timeout expires. +---@param chan integer -- servo channel number (zero indexed) +---@param pwm integer -- pwm value +---@param timeout_ms integer -- duration of the override function SRV_Channels:set_output_pwm_chan_timeout(chan, pwm, timeout_ms) end --- desc ----@param chan integer ----@param pwm integer +-- Set the pwm for a given servo output channel +---@param chan integer -- servo channel number (zero indexed) +---@param pwm integer -- pwm value function SRV_Channels:set_output_pwm_chan(chan, pwm) end --- desc ----@param function_num integer ----@param pwm integer +-- Set the pwm for a given servo output function +---@param function_num integer -- servo function number (See SERVOx_FUNCTION parameters) +---@param pwm integer -- pwm value function SRV_Channels:set_output_pwm(function_num, pwm) end --- desc ----@param function_num integer ----@return integer|nil +-- Returns first servo output number (zero indexed) of an output assigned output_function (See SERVOx_FUNCTION parameters ). 0 = SERVO1_FUNCTION ect. Nil if none is assigned. +---@param function_num integer -- servo function (See SERVOx_FUNCTION parameters) +---@return integer|nil -- output channel number if available function SRV_Channels:find_channel(function_num) end --- desc +-- This library allows the control of RGB LED strings via an output reserved for scripting and selected by SERVOx_FUNCTION = 94 thru 109 (Script Out 1 thru 16) serialLED = {} --- desc ----@param chan integer ----@return boolean +-- Send the configured RGB values to the LED string +---@param chan integer -- output number to which the leds are attached 1-16 +---@return boolean -- true if successful function serialLED:send(chan) end --- desc ----@param chan integer ----@param led_index integer ----@param red integer ----@param green integer ----@param blue integer ----@return boolean +-- Set the data for LED_number on the string attached channel output +---@param chan integer -- output number to which the leds are attached 1-16 +---@param led_index integer -- led number 0 index, -1 sets all +---@param red integer -- red value 0 to 255 +---@param green integer -- green value 0 to 255 +---@param blue integer -- blue value 0 to 255 +---@return boolean -- true if successful function serialLED:set_RGB(chan, led_index, red, green, blue) end --- desc ----@param chan integer ----@param num_leds integer ----@return boolean +-- Sets the number of LEDs in a profiled string on a servo output. +---@param chan integer -- output number to which the leds are attached 1-16 +---@param num_leds integer -- number of leds in the string +---@return boolean -- true if successful function serialLED:set_num_profiled(chan, num_leds) end --- desc ----@param chan integer ----@param num_leds integer ----@return boolean +-- Sets the number of LEDs in a neopixel string on a servo output. +---@param chan integer -- output number to which the leds are attached 1-16 +---@param num_leds integer -- number of leds in the string +---@return boolean -- true if successful function serialLED:set_num_neopixel(chan, num_leds) end --- desc ----@param chan integer ----@param num_leds integer ----@return boolean +-- Sets the number of LEDs in a rgb neopixel string on a servo output. +---@param chan integer -- output number to which the leds are attached 1-16 +---@param num_leds integer -- number of leds in the string +---@return boolean -- true if successful function serialLED:set_num_neopixel_rgb(chan, num_leds) end -- desc @@ -2225,9 +2235,9 @@ function vehicle:get_circle_radius() end ---@return boolean function vehicle:set_target_angle_and_climbrate(roll_deg, pitch_deg, yaw_deg, climb_rate_ms, use_yaw_rate, yaw_rate_degs) end --- desc ----@param vel_ned Vector3f_ud ----@return boolean +-- Sets the target velocity using a Vector3f object in a guided mode. +---@param vel_ned Vector3f_ud -- North, East, Down meters / second +---@return boolean -- true on success function vehicle:set_target_velocity_NED(vel_ned) end -- desc @@ -2276,18 +2286,18 @@ function vehicle:set_target_pos_NED(target_pos, use_yaw, yaw_deg, use_yaw_rate, ---@return boolean function vehicle:update_target_location(current_target, new_target) end --- desc ----@return Location_ud|nil +-- Get the current target location if available in current mode +---@return Location_ud|nil -- target location function vehicle:get_target_location() end --- desc ----@param target_loc Location_ud ----@return boolean +-- Set the target veicle location in a guided mode +---@param target_loc Location_ud -- target location +---@return boolean -- true on success function vehicle:set_target_location(target_loc) end --- desc ----@param alt number ----@return boolean +-- Trigger a takeoff start if in a auto or guided mode. Not supported by all vehicles +---@param alt number -- takeoff altitude in meters +---@return boolean -- true on success function vehicle:start_takeoff(alt) end -- desc @@ -2303,25 +2313,25 @@ function vehicle:start_takeoff(alt) end ---@return number|nil function vehicle:get_control_output(control_output) end --- desc ----@return uint32_t_ud +-- Returns time in milliseconds since the autopilot thinks it started flying, or zero if not currently flying. +---@return uint32_t_ud -- flying time in milliseconds function vehicle:get_time_flying_ms() end --- desc ----@return boolean +-- Returns true if the autopilot thinks it is flying. Not guaranteed to be accurate. +---@return boolean -- true if likely flying function vehicle:get_likely_flying() end -- desc ---@return integer function vehicle:get_control_mode_reason() end --- desc ----@return integer +-- Returns current vehicle mode by mode_number. +---@return integer -- mode number. Values for each vehcile type can be found here: https://mavlink.io/en/messages/ardupilotmega.html#PLANE_MODE function vehicle:get_mode() end --- desc ----@param mode_number integer ----@return boolean +-- Attempts to change vehicle mode to mode_number. Returns true if successful, false if mode change is not successful. +---@param mode_number integer -- mode number values for each vehcile type can be found here: https://mavlink.io/en/messages/ardupilotmega.html#PLANE_MODE +---@return boolean -- success function vehicle:set_mode(mode_number) end -- desc @@ -2497,59 +2507,62 @@ function gcs:send_text(severity, text) end ---@return uint32_t_ud -- system time in milliseconds function gcs:last_seen() end --- desc +-- The relay library provides access to controlling relay outputs. relay = {} --- desc ----@param instance integer +-- Toggles the requested relay from on to off or from off to on. +---@param instance integer -- relay instance function relay:toggle(instance) end --- desc ----@param instance integer +-- Returns true if the requested relay is enabled. +---@param instance integer -- relay instance ---@return boolean function relay:enabled(instance) end -- return state of a relay ----@param instance integer ----@return integer +---@param instance integer -- relay instance +---@return integer -- relay state function relay:get(instance) end --- desc ----@param instance integer +-- Turns the requested relay off. +---@param instance integer -- relay instance function relay:off(instance) end --- desc ----@param instance integer +-- Turns the requested relay on. +---@param instance integer -- relay instance function relay:on(instance) end --- desc +-- The terrain library provides access to checking heights against a terrain database. terrain = {} terrain.TerrainStatusOK = enum_integer terrain.TerrainStatusUnhealthy = enum_integer terrain.TerrainStatusDisabled = enum_integer --- desc +-- Returns the height (in meters) that the vehicle is currently above the terrain, or returns nil if that is not available. +-- If extrapolate is true then allow return of an extrapolated terrain altitude based on the last available data ---@param extrapolate boolean ----@return number|nil +---@return number|nil -- height above terrain in meters if available function terrain:height_above_terrain(extrapolate) end --- desc +-- find difference between home terrain height and the terrain height at the current location in meters. A positive result means the terrain is higher than home. +-- return false is terrain at the current location or at home location is not available +-- If extrapolate is true then allow return of an extrapolated terrain altitude based on the last available data ---@param extrapolate boolean ----@return number|nil +---@return number|nil -- height difference in meters if available function terrain:height_terrain_difference_home(extrapolate) end --- desc ----@param loc Location_ud ----@param corrected boolean ----@return number|nil +-- Returns the terrain height (in meters) above mean sea level at the provided Location userdata, or returns nil if that is not available. +---@param loc Location_ud -- location at which to lookup terrain +---@param corrected boolean -- if true the terrain altitude should be correced based on the diffrence bettween the database and measured altitude at home +---@return number|nil -- amsl altitude of terrain at given locaiton in meters function terrain:height_amsl(loc, corrected) end --- desc ----@return integer +-- Returns the current status of the terrain. Compare this to one of the terrain statuses (terrain.TerrainStatusDisabled, terrain.TerrainStatusUnhealthy, terrain.TerrainStatusOK). +---@return integer -- terrain status function terrain:status() end --- desc +-- Returns true if terrain is enabled. ---@return boolean function terrain:enabled() end @@ -2782,7 +2795,8 @@ function notify:handle_rgb_id(red, green, blue, id) end ---@param rate_hz integer function notify:handle_rgb(red, green, blue, rate_hz) end --- desc +-- Plays a MML tune through the buzzer on the vehicle. The tune is provided as a string. +-- An online tune tester can be found here: https://firmware.ardupilot.org/Tools/ToneTester/ ---@param tune string function notify:play_tune(tune) end @@ -2795,111 +2809,114 @@ function notify:send_text(text, row) end ---@param row integer function notify:release_text(row) end --- desc +-- The GPS library provides access to information about the GPS’s on the vehicle. gps = {} ---gps.GPS_OK_FIX_3D_RTK_FIXED = enum_integer ---gps.GPS_OK_FIX_3D_RTK_FLOAT = enum_integer ---gps.GPS_OK_FIX_3D_DGPS = enum_integer ---gps.GPS_OK_FIX_3D = enum_integer ---gps.GPS_OK_FIX_2D = enum_integer ---gps.NO_FIX = enum_integer ---gps.NO_GPS = enum_integer - --- desc +gps.GPS_OK_FIX_3D_RTK_FIXED = enum_integer +gps.GPS_OK_FIX_3D_RTK_FLOAT = enum_integer +gps.GPS_OK_FIX_3D_DGPS = enum_integer +gps.GPS_OK_FIX_3D = enum_integer +gps.GPS_OK_FIX_2D = enum_integer +gps.NO_FIX = enum_integer +gps.NO_GPS = enum_integer + +-- Returns nil or the instance number of the first GPS that has not been fully configured. If all GPS’s have been configured this returns nil. ---@return integer|nil function gps:first_unconfigured_gps() end --- desc ----@param instance integer ----@return Vector3f_ud +-- Returns a Vector3f that contains the offsets of the GPS in meters in the body frame. +---@param instance integer -- instance number +---@return Vector3f_ud -- anteena offset vector forward, right, down in meters function gps:get_antenna_offset(instance) end --- desc ----@param instance integer ----@return boolean +-- Returns true if the GPS instance can report the vertical velocity. +---@param instance integer -- instance number +---@return boolean -- true if vertical velocity is available function gps:have_vertical_velocity(instance) end -- desc ----@param instance integer +---@param instance integer -- instance number ---@return uint32_t_ud function gps:last_message_time_ms(instance) end --- desc ----@param instance integer ----@return uint32_t_ud +-- Returns the time of the last fix in system milliseconds. +---@param instance integer -- instance number +---@return uint32_t_ud -- system time of last fix in milliseconds function gps:last_fix_time_ms(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the vertical dilution of precision of the GPS instance. +---@param instance integer -- instance number +---@return integer -- vdop function gps:get_vdop(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the horizontal dilution of precision of the GPS instance. +---@param instance integer -- instance number +---@return integer -- hdop function gps:get_hdop(instance) end --- desc ----@param instance integer ----@return uint32_t_ud +-- Returns the number of milliseconds into the current week. +---@param instance integer -- instance number +---@return uint32_t_ud -- milliseconds of current week function gps:time_week_ms(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the GPS week number. +---@param instance integer -- instance number +---@return integer -- week number function gps:time_week(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the number of satellites that the GPS is currently tracking. +---@param instance integer -- instance number +---@return integer -- number of satellites function gps:num_sats(instance) end --- desc ----@param instance integer ----@return number +-- Returns the ground course of the vehicle in degrees. You must check the status to know if the ground course is still current. +---@param instance integer -- instance number +---@return number -- ground course in degrees function gps:ground_course(instance) end --- desc ----@param instance integer ----@return number +-- Returns the ground speed of the vehicle in meters per second. You must check the status to know if the ground speed is still current. +---@param instance integer -- instance number +---@return number -- ground speed m/s function gps:ground_speed(instance) end --- desc ----@param instance integer ----@return Vector3f_ud +-- Returns a Vector3f that contains the velocity as observed by the GPS. +-- You must check the status to know if the velocity is still current. +---@param instance integer -- instance number +---@return Vector3f_ud -- 3D velocity in m/s, in NED format function gps:velocity(instance) end -- desc ----@param instance integer +---@param instance integer -- instance number ---@return number|nil function gps:vertical_accuracy(instance) end --- desc ----@param instance integer ----@return number|nil +-- horizontal RMS accuracy estimate in m +---@param instance integer -- instance number +---@return number|nil -- accuracy in meters function gps:horizontal_accuracy(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns nil, or the speed accuracy of the GPS in meters per second, if the information is available for the GPS instance. +---@param instance integer -- instance number +---@return number|nil -- 3D velocity RMS accuracy estimate in m/s if available function gps:speed_accuracy(instance) end --- desc ----@param instance integer ----@return Location_ud +-- eturns a Location userdata for the last GPS position. You must check the status to know if the location is still current, if it is NO_GPS, or NO_FIX then it will be returning old data. +---@param instance integer -- instance number +---@return Location_ud --gps location function gps:location(instance) end --- desc ----@param instance integer ----@return integer +-- Returns the GPS fix status. Compare this to one of the GPS fix types. +-- Posible status are provided as values on the gps object. eg: gps.GPS_OK_FIX_3D +---@param instance integer -- instance number +---@return integer -- status function gps:status(instance) end --- desc ----@return integer +-- Returns which GPS is currently being used as the primary GPS device. +---@return integer -- primary sensor instance function gps:primary_sensor() end --- desc ----@return integer +-- Returns the number of connected GPS devices. +-- If GPS blending is turned on that will show up as the third sensor, and be reported here. +---@return integer -- number of sensors function gps:num_sensors() end -- desc @@ -2950,7 +2967,7 @@ function BattMonitorScript_State_ud:voltage(value) end ---@param value boolean function BattMonitorScript_State_ud:healthy(value) end --- desc +-- The battery library provides access to information about the currently connected batteries on the vehicle. battery = {} -- desc @@ -2960,72 +2977,72 @@ battery = {} function battery:handle_scripting(idx, state) end -- desc ----@param instance integer +---@param instance integer -- battery instance ---@param percentage number ---@return boolean function battery:reset_remaining(instance, percentage) end --- desc ----@param instance integer ----@return integer|nil +-- Returns cycle count of the battery or nil if not available. +---@param instance integer -- battery instance +---@return integer|nil -- cycle count if available function battery:get_cycle_count(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns the temperature of the battery in degrees Celsius if the battery supports temperature monitoring. +---@param instance integer -- battery instance +---@return number|nil -- temperature if available function battery:get_temperature(instance) end --- desc ----@param instance integer ----@return boolean +-- returns true if too much power is being drawn from the battery being monitored. +---@param instance integer -- battery instance +---@return boolean -- true if in overpower condition function battery:overpower_detected(instance) end --- desc ----@return boolean +-- Returns true if any of the batteries being monitored have triggered a failsafe. +---@return boolean -- true if any battery has failsafed function battery:has_failsafed() end --- desc ----@param instance integer ----@return integer +-- Returns the full pack capacity (in milliamp hours) from the battery. +---@param instance integer -- battery instance +---@return integer -- capacity in milliamp hours function battery:pack_capacity_mah(instance) end --- desc ----@param instance integer ----@return integer|nil +-- Returns the remaining percentage of battery (from 0 to 100), or nil if energy monitoring is not available. +---@param instance integer -- battery instance +---@return integer|nil -- remaining capacity as a percentage of total capacity if available function battery:capacity_remaining_pct(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns the used watt hours from the battery, or nil if energy monitoring is not available. +---@param instance integer -- battery instance +---@return number|nil -- consumed energy in watt hours if available function battery:consumed_wh(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns the capacity (in milliamp hours) used from the battery, or nil if current monitoring is not available. +---@param instance integer -- battery instance +---@return number|nil -- consumed capacity in milliamp hours function battery:consumed_mah(instance) end --- desc ----@param instance integer ----@return number|nil +-- Returns the current (in Amps) that is currently being consumed by the battery, or nil if current monitoring is not available. +---@param instance integer -- battery instance +---@return number|nil -- current in amps if available function battery:current_amps(instance) end --- desc ----@param instance integer ----@return number +-- Returns the estimated battery voltage if it was not under load. +---@param instance integer -- battery instance +---@return number -- resting voltage function battery:voltage_resting_estimate(instance) end --- desc ----@param instance integer ----@return number +-- Returns the voltage of the selected battery instance. +---@param instance integer -- battery instance +---@return number -- voltage function battery:voltage(instance) end --- desc ----@param instance integer +-- Returns true if the requested battery instance is healthy. Healthy is considered to be ArduPilot is currently able to monitor the battery. +---@param instance integer -- battery instance ---@return boolean function battery:healthy(instance) end --- desc ----@return integer +-- Returns the number of battery instances currently available. +---@return integer -- number of instances function battery:num_instances() end -- get individual cell voltage @@ -3035,7 +3052,7 @@ function battery:num_instances() end function battery:get_cell_voltage(instance, cell) end --- desc +-- The Arming library provides access to arming status and commands. arming = {} -- desc @@ -3051,24 +3068,25 @@ function arming:set_aux_auth_passed(auth_id) end ---@return integer|nil function arming:get_aux_auth_id() end --- desc ----@return boolean +-- Attempts to arm the vehicle. Returns true if successful. +---@return boolean -- true if armed successfully function arming:arm() end --- desc ----@return boolean +-- Returns a true if vehicle is currently armed. +---@return boolean -- true if armed function arming:is_armed() end -- desc ---@return boolean function arming:pre_arm_checks() end --- desc ----@return boolean +-- Disarms the vehicle in all cases. Returns false only if already disarmed. +---@return boolean -- true if disarmed successfully, false if already disarmed. function arming:disarm() end --- desc +-- The ahrs library represents the Attitude Heading Reference System computed by the autopilot. +-- It provides estimates for the vehicles attitude, and position. ahrs = {} -- desc @@ -3133,16 +3151,16 @@ function ahrs:earth_to_body(vector) end ---@return Vector3f_ud function ahrs:get_vibration() end --- desc ----@return number|nil +-- Return the estimated airspeed of the vehicle if available +---@return number|nil -- airspeed in meters / second if available function ahrs:airspeed_estimate() end -- desc ---@return boolean function ahrs:healthy() end --- desc ----@return boolean +-- Returns a true if home position has been set. +---@return boolean -- true if home position has been set function ahrs:home_is_set() end -- desc @@ -3157,16 +3175,16 @@ function ahrs:get_relative_position_NED_origin() end ---@return Vector3f_ud|nil function ahrs:get_relative_position_NED_home() end --- desc ----@return Vector3f_ud|nil +-- Returns nil, or a Vector3f containing the current NED vehicle velocity in meters/second in north, east, and down components. +---@return Vector3f_ud|nil -- North, east, down velcoity in meters / second if available function ahrs:get_velocity_NED() end --- desc ----@return Vector2f_ud +-- Get current groundspeed vector in meter / second +---@return Vector2f_ud -- ground speed vector, North East, meters / second function ahrs:groundspeed_vector() end --- desc ----@return Vector3f_ud +-- Returns a Vector3f containing the current wind estimate for the vehicle. +---@return Vector3f_ud -- wind estiamte North, East, Down meters / second function ahrs:wind_estimate() end -- Determine how aligned heading_deg is with the wind. Return result @@ -3181,40 +3199,41 @@ function ahrs:wind_alignment(heading_deg) end ---@return number function ahrs:head_wind() end --- desc ----@return number|nil +-- Returns nil, or the latest altitude estimate above ground level in meters +---@return number|nil -- height above ground level in meters function ahrs:get_hagl() end -- desc ---@return Vector3f_ud function ahrs:get_accel() end --- desc ----@return Vector3f_ud +-- Returns a Vector3f containing the current smoothed and filtered gyro rates (in radians/second) +---@return Vector3f_ud -- roll, pitch, yaw gyro rates in radians / second function ahrs:get_gyro() end --- desc ----@return Location_ud +-- Returns a Location that contains the vehicles current home waypoint. +---@return Location_ud -- home location function ahrs:get_home() end --- desc ----@return Location_ud|nil +-- Returns nil or Location userdata that contains the vehicles current position. +-- Note: This will only return a Location if the system considers the current estimate to be reasonable. +---@return Location_ud|nil -- current location if available function ahrs:get_location() end -- same as `get_location` will be removed ---@return Location_ud|nil function ahrs:get_position() end --- desc ----@return number +-- Returns the current vehicle euler yaw angle in radians. +---@return number -- yaw angle in radians. function ahrs:get_yaw() end --- desc ----@return number +-- Returns the current vehicle euler pitch angle in radians. +---@return number -- pitch angle in radians. function ahrs:get_pitch() end --- desc ----@return number +-- Returns the current vehicle euler roll angle in radians. +---@return number -- roll angle in radians function ahrs:get_roll() end -- desc