pub struct SET_HOME_POSITION_DATA {
pub latitude: i32,
pub longitude: i32,
pub altitude: i32,
pub x: f32,
pub y: f32,
pub z: f32,
pub q: [f32; 4],
pub approach_x: f32,
pub approach_y: f32,
pub approach_z: f32,
pub target_system: u8,
pub time_usec: u64,
}
avssuas
only.Expand description
id: 243 Sets the home position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)..
Fields§
§latitude: i32
Latitude (WGS84).
longitude: i32
Longitude (WGS84).
altitude: i32
Altitude (MSL). Positive for up..
x: f32
Local X position of this position in the local coordinate frame (NED).
y: f32
Local Y position of this position in the local coordinate frame (NED).
z: f32
Local Z position of this position in the local coordinate frame (NED: positive “down”).
q: [f32; 4]
World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground.
approach_x: f32
Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone..
approach_y: f32
Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone..
approach_z: f32
Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone..
target_system: u8
System ID..
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..
Implementations§
Source§impl SET_HOME_POSITION_DATA
impl SET_HOME_POSITION_DATA
pub const ENCODED_LEN: usize = 61usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for SET_HOME_POSITION_DATA
impl Clone for SET_HOME_POSITION_DATA
Source§fn clone(&self) -> SET_HOME_POSITION_DATA
fn clone(&self) -> SET_HOME_POSITION_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more