Struct ros2_client::Server

source ·
pub struct Server<S>
where S: Service, S::Request: Message, S::Response: Message,
{ /* private fields */ }
Expand description

Server end of a ROS2 Service

Implementations§

source§

impl<S> Server<S>
where S: 'static + Service,

source

pub fn receive_request(&self) -> ReadResult<Option<(RmwRequestId, S::Request)>>

Receive a request from Client. Returns Ok(None) if no new requests have arrived.

source

pub fn send_response( &self, rmw_req_id: RmwRequestId, response: S::Response ) -> WriteResult<(), ()>

Send response to request by Client. rmw_req_id identifies request being responded.

source

pub async fn async_receive_request( &self ) -> ReadResult<(RmwRequestId, S::Request)>

The request_id must be sent back with the response to identify which request and response belong together.

source

pub fn receive_request_stream( &self ) -> impl FusedStream<Item = ReadResult<(RmwRequestId, S::Request)>> + '_

Returns a never-ending stream of (request_id, request) The request_id must be sent back with the response to identify which request and response belong together.

source

pub async fn async_send_response( &self, rmw_req_id: RmwRequestId, response: S::Response ) -> WriteResult<(), ()>

Asynchronous response sending

Trait Implementations§

source§

impl<S> Evented for Server<S>
where S: 'static + Service,

source§

fn register( &self, poll: &Poll, token: Token, interest: Ready, opts: PollOpt ) -> Result<()>

Register self with the given Poll instance. Read more
source§

fn reregister( &self, poll: &Poll, token: Token, interest: Ready, opts: PollOpt ) -> Result<()>

Re-register self with the given Poll instance. Read more
source§

fn deregister(&self, poll: &Poll) -> Result<()>

Deregister self from the given Poll instance Read more

Auto Trait Implementations§

§

impl<S> !Freeze for Server<S>

§

impl<S> !RefUnwindSafe for Server<S>

§

impl<S> Send for Server<S>
where <S as Service>::Response: for<'de> Sized + Send, <S as Service>::Request: for<'de> Sized + Send,

§

impl<S> Sync for Server<S>
where <S as Service>::Response: for<'de> Sized + Sync, <S as Service>::Request: for<'de> Sized + Sync,

§

impl<S> Unpin for Server<S>
where <S as Service>::Response: for<'de> Sized + Unpin, <S as Service>::Request: for<'de> Sized + Unpin,

§

impl<S> !UnwindSafe for Server<S>

Blanket Implementations§

source§

impl<T> Any for T
where T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for T
where T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T, U> Into<U> for T
where U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

§

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

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

source§

fn vzip(self) -> V