Struct ros2_client::Client

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

Client end of a ROS2 Service

Implementations§

source§

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

source

pub fn send_request(&self, request: S::Request) -> WriteResult<RmwRequestId, ()>

Send a request to Service Server. The returned RmwRequestId is a token to identify the correct response.

source

pub fn receive_response( &self ) -> ReadResult<Option<(RmwRequestId, S::Response)>>

Receive a response from Server Returns Ok(None) if no new responses have arrived. Note: The response may to someone else’s request. Check received RmWRequestId against the one you got when sending request to identify the correct response. In case you receive someone else’s response, please do receive again.

source

pub async fn async_send_request( &self, request: S::Request ) -> WriteResult<RmwRequestId, ()>

Send a request to Service Server asynchronously. The returned RmwRequestId is a token to identify the correct response.

source

pub async fn async_receive_response( &self, request_id: RmwRequestId ) -> ReadResult<S::Response>

Receive a response from Server The returned Future does not complete until the response has been received.

source

pub async fn async_call_service( &self, request: S::Request ) -> Result<S::Response, CallServiceError<()>>

source

pub async fn wait_for_service(&self, my_node: &Node)

Wait for a Server to be connected to the Request and Response topics.

This does not distinguish between diagnostinc tools and actual servers. It is enough that someone has subscribed the Requests, and someone is a publisher for Responses.

May panic, if the Node does not havea background Spinner running.

Trait Implementations§

source§

impl<S> Evented for Client<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 Client<S>

§

impl<S> !RefUnwindSafe for Client<S>

§

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

§

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

§

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

§

impl<S> !UnwindSafe for Client<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