[][src]Struct toio::proto::MotorMultiTarget

pub struct MotorMultiTarget {
    pub id: u8,
    pub timeout: u8,
    pub move_type: MoveType,
    pub max_speed: u8,
    pub speed_change: SpeedChange,
    pub reserved: u8,
    pub writeopt: WriteOpt,
    pub targets: Vec<Target>,
}

The request to visit multiple target positions.

Fields

id: u8

The request id to find the corresponding response to this request.

timeout: u8

The timeout in seconds.

move_type: MoveType

The type of the movement.

max_speed: u8

The maximum speed.

speed_change: SpeedChange

The change of the speed during movement.

reserved: u8

Unused.

writeopt: WriteOpt

The option for additional requests.

targets: Vec<Target>

The list of target positions to visit.

Implementations

impl MotorMultiTarget[src]

pub fn new(
    id: u8,
    timeout: u8,
    move_type: MoveType,
    max_speed: u8,
    speed_change: SpeedChange,
    writeopt: WriteOpt,
    targets: Vec<Target>
) -> Self
[src]

Constructs a new MotorMultiTarget.

Trait Implementations

impl Clone for MotorMultiTarget[src]

impl Debug for MotorMultiTarget[src]

impl<'de> Deserialize<'de> for MotorMultiTarget[src]

impl Eq for MotorMultiTarget[src]

impl PartialEq<MotorMultiTarget> for MotorMultiTarget[src]

impl Serialize for MotorMultiTarget[src]

impl StructuralEq for MotorMultiTarget[src]

impl StructuralPartialEq for MotorMultiTarget[src]

Auto Trait Implementations

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> DeserializeOwned for T where
    T: for<'de> Deserialize<'de>, 
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T> ToOwned for T where
    T: Clone
[src]

type Owned = T

The resulting type after obtaining ownership.

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.