diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index bc9d895571..83cb58dfd6 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1882,6 +1882,58 @@ function gcs:send_named_float(name, value) end ---| '4' # Failed function gcs:set_message_interval(port_num, msg_id, interval_us) end +-- get the vehicle MAV_TYPE +---@return integer +---| '0' # MAV_TYPE_GENERIC=0, /* Generic micro air vehicle | */ +---| '1' # MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ +---| '2' # MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ +---| '3' # MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ +---| '4' # MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ +---| '5' # MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ +---| '6' # MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ +---| '7' # MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ +---| '8' # MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ +---| '9' # MAV_TYPE_ROCKET=9, /* Rocket | */ +---| '10' # MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ +---| '11' # MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ +---| '12' # MAV_TYPE_SUBMARINE=12, /* Submarine | */ +---| '13' # MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ +---| '14' # MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ +---| '15' # MAV_TYPE_TRICOPTER=15, /* Tricopter | */ +---| '16' # MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ +---| '17' # MAV_TYPE_KITE=17, /* Kite | */ +---| '18' # MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */ +---| '19' # MAV_TYPE_VTOL_DUOROTOR=19, /* Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. | */ +---| '20' # MAV_TYPE_VTOL_QUADROTOR=20, /* Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. | */ +---| '21' # MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL | */ +---| '22' # MAV_TYPE_VTOL_RESERVED2=22, /* VTOL reserved 2 | */ +---| '23' # MAV_TYPE_VTOL_RESERVED3=23, /* VTOL reserved 3 | */ +---| '24' # MAV_TYPE_VTOL_RESERVED4=24, /* VTOL reserved 4 | */ +---| '25' # MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */ +---| '26' # MAV_TYPE_GIMBAL=26, /* Gimbal | */ +---| '27' # MAV_TYPE_ADSB=27, /* ADSB system | */ +---| '28' # MAV_TYPE_PARAFOIL=28, /* Steerable, nonrigid airfoil | */ +---| '29' # MAV_TYPE_DODECAROTOR=29, /* Dodecarotor | */ +---| '30' # MAV_TYPE_CAMERA=30, /* Camera | */ +---| '31' # MAV_TYPE_CHARGING_STATION=31, /* Charging station | */ +---| '32' # MAV_TYPE_FLARM=32, /* FLARM collision avoidance system | */ +---| '33' # MAV_TYPE_SERVO=33, /* Servo | */ +---| '34' # MAV_TYPE_ODID=34, /* Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. | */ +---| '35' # MAV_TYPE_DECAROTOR=35, /* Decarotor | */ +---| '36' # MAV_TYPE_BATTERY=36, /* Battery | */ +---| '37' # MAV_TYPE_PARACHUTE=37, /* Parachute | */ +---| '38' # MAV_TYPE_LOG=38, /* Log | */ +---| '39' # MAV_TYPE_OSD=39, /* OSD | */ +---| '40' # MAV_TYPE_IMU=40, /* IMU | */ +---| '41' # MAV_TYPE_GPS=41, /* GPS | */ +---| '42' # MAV_TYPE_WINCH=42, /* Winch | */ +---| '43' # MAV_TYPE_ENUM_END=43, /* | */ +function gcs:frame_type() end + +-- get the throttle value in % +---@return integer +function gcs:get_hud_throttle() end + -- set high latency control state. Analogous to MAV_CMD_CONTROL_HIGH_LATENCY ---@param enabled boolean -- true to enable or false to disable ---@return void diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index d0c876b92f..2e4ac09b45 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -225,6 +225,8 @@ singleton GCS rename gcs singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG "%s"'literal string singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t'skip_check int32_t -1 INT32_MAX singleton GCS method send_named_float void string float'skip_check +singleton GCS method frame_type MAV_TYPE'enum +singleton GCS method get_hud_throttle int16_t singleton GCS depends HAL_HIGH_LATENCY2_ENABLED == 1 singleton GCS method get_high_latency_status boolean