pub struct Waypoint {
pub index: u16,
pub current: bool,
pub frame: MavFrame,
pub command: WaypointCommand,
pub param1: f32,
pub param2: f32,
pub param3: f32,
pub param4: f32,
pub x: f64,
pub y: f64,
pub z: f32,
pub autocontinue: bool,
}Expand description
⍚ MAVLink mission waypoint.
Fields§
§index: u16Waypoint index.
current: boolIs a current MAVLink waypoint.
frame: MavFrameMAVLink field frame.
The coordinate system of the waypoint.
command: WaypointCommandMAVLink field command.
The scheduled action for the waypoint.
param1: f32MAVLink command field param1.
param2: f32MAVLink command field param2.
param3: f32MAVLink command field param3.
param4: f32MAVLink command field param4.
x: f64MAVLink command field x.
PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
y: f64MAVLink command field y.
PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
z: f32MAVLink command field z.
PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
autocontinue: boolMAVLink field autocontinue.
Autocontinue to next waypoint. Set false to pause mission after the item completes.
Implementations§
Source§impl Waypoint
impl Waypoint
Sourcepub fn to_mission_item(&self, target_id: MavLinkId) -> MissionItem
pub fn to_mission_item(&self, target_id: MavLinkId) -> MissionItem
Converts waypoint into a MissionItem message.
Sourcepub fn as_str_buffered<'a>(
&self,
buf: &'a mut [u8],
) -> Result<&'a str, MissionError>
pub fn as_str_buffered<'a>( &self, buf: &'a mut [u8], ) -> Result<&'a str, MissionError>
Tries to create an &str representations of waypoint using a provided buffer.
Supports no-alloc targets. Use to_string otherwise.
Sourcepub fn as_bytes_buffered<'a>(
&self,
buf: &'a mut [u8],
) -> Result<&'a [u8], MissionError>
pub fn as_bytes_buffered<'a>( &self, buf: &'a mut [u8], ) -> Result<&'a [u8], MissionError>
Tries to create a byte representations of waypoint using a provided buffer.
Supports no-alloc targets. Use to_string and pass its result as bytes otherwise.
Trait Implementations§
Source§impl<'de> Deserialize<'de> for Waypoint
impl<'de> Deserialize<'de> for Waypoint
Source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
Source§impl NamedType for Waypoint
impl NamedType for Waypoint
fn sid() -> SpectaID
Source§fn named_data_type(
type_map: &mut TypeCollection,
generics: &[DataType],
) -> NamedDataType
fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType
Source§fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
Source§impl TryFrom<MissionItem> for Waypoint
impl TryFrom<MissionItem> for Waypoint
Source§impl Type for Waypoint
impl Type for Waypoint
Source§fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
Source§fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
definition will be put into the type map.