mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Scripting: add binding for GPS time_epoch_usec
This commit is contained in:
parent
1c26c241f1
commit
a322ba4f77
@ -2897,6 +2897,11 @@ gps.GPS_OK_FIX_2D = enum_integer
|
||||
gps.NO_FIX = enum_integer
|
||||
gps.NO_GPS = enum_integer
|
||||
|
||||
-- get unix time
|
||||
---@param instance integer -- instance number
|
||||
---@return uint64_t_ud -- unix time microseconds
|
||||
function gps:time_epoch_usec(instance) end
|
||||
|
||||
-- get yaw from GPS in degrees
|
||||
---@param instance integer -- instance number
|
||||
---@return number|nil -- yaw in degrees
|
||||
|
@ -135,6 +135,7 @@ singleton AP_GPS method have_vertical_velocity boolean uint8_t 0 ud->num_sensors
|
||||
singleton AP_GPS method get_antenna_offset Vector3f uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method first_unconfigured_gps boolean uint8_t'Null
|
||||
singleton AP_GPS method gps_yaw_deg boolean uint8_t 0 ud->num_sensors() float'Null float'Null uint32_t'Null
|
||||
singleton AP_GPS method time_epoch_usec uint64_t uint8_t 0 ud->num_sensors()
|
||||
|
||||
include AP_Math/AP_Math.h
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user