pub struct ORBIT_EXECUTION_STATUS_DATA {
pub time_usec: u64,
pub radius: f32,
pub x: i32,
pub y: i32,
pub z: f32,
pub frame: MavFrame,
}
paparazzi
only.Expand description
id: 360 Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)..
Fields§
§time_usec: u64
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number..
radius: f32
Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise..
x: i32
X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7..
y: i32
Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7..
z: f32
Altitude of center point. Coordinate system depends on frame field..
frame: MavFrame
The coordinate system of the fields: x, y, z..
Implementations§
Source§impl ORBIT_EXECUTION_STATUS_DATA
impl ORBIT_EXECUTION_STATUS_DATA
pub const ENCODED_LEN: usize = 25usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for ORBIT_EXECUTION_STATUS_DATA
impl Clone for ORBIT_EXECUTION_STATUS_DATA
Source§fn clone(&self) -> ORBIT_EXECUTION_STATUS_DATA
fn clone(&self) -> ORBIT_EXECUTION_STATUS_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more