pub struct Node {
pub params: Arc<Mutex<IndexMap<String, Parameter>>>,
/* private fields */
}
Expand description
A ROS Node.
This struct owns all subscribes, publishers, etc. To get events
from the ROS network into your ros application, spin_once
should
be called continously.
Fields§
§params: Arc<Mutex<IndexMap<String, Parameter>>>
ROS parameters.
Implementations§
source§impl Node
impl Node
sourcepub fn fully_qualified_name(&self) -> Result<String>
pub fn fully_qualified_name(&self) -> Result<String>
Returns the fully qualified name of the node.
sourcepub fn make_parameter_handler(
&mut self,
) -> Result<(impl Future<Output = ()> + Send, impl Stream<Item = (String, ParameterValue)>)>
pub fn make_parameter_handler( &mut self, ) -> Result<(impl Future<Output = ()> + Send, impl Stream<Item = (String, ParameterValue)>)>
Creates parameter service handlers for the Node.
This function returns a tuple (Future
, Stream
), where the
future should be spawned on onto the executor of choice. The
Stream
produces events whenever parameters change from
external sources. The event elements of the event stream
include the name of the parameter which was updated as well as
its new value.
sourcepub fn make_derived_parameter_handler(
&mut self,
params_struct: Arc<Mutex<dyn RosParams + Send>>,
) -> Result<(impl Future<Output = ()> + Send, impl Stream<Item = (String, ParameterValue)>)>
pub fn make_derived_parameter_handler( &mut self, params_struct: Arc<Mutex<dyn RosParams + Send>>, ) -> Result<(impl Future<Output = ()> + Send, impl Stream<Item = (String, ParameterValue)>)>
Creates parameter service handlers for the Node based on the
RosParams
trait.
Supported parameter names and types are given by the
params_struct
parameter (usually referring to a structure).
Fields of the structure will be updated based on the command
line parameters (if any) and later whenever a parameter gets
changed from external sources. Updated fields will be visible
outside of the node via the GetParameters service.
This function returns a tuple (Future
, Stream
), where the
future should be spawned on onto the executor of choice. The
Stream
produces events whenever parameters change from
external sources. The event elements of the event stream
include the name of the parameter which was updated as well as
its new value.
sourcepub fn get_parameter<T>(&self, name: &str) -> Result<T>
pub fn get_parameter<T>(&self, name: &str) -> Result<T>
Fetch a single ROS parameter.
sourcepub fn subscribe<T>(
&mut self,
topic: &str,
qos_profile: QosProfile,
) -> Result<impl Stream<Item = T> + Unpin>where
T: WrappedTypesupport + 'static,
pub fn subscribe<T>(
&mut self,
topic: &str,
qos_profile: QosProfile,
) -> Result<impl Stream<Item = T> + Unpin>where
T: WrappedTypesupport + 'static,
Subscribe to a ROS topic.
This function returns a Stream
of ros messages.
sourcepub fn subscribe_native<T>(
&mut self,
topic: &str,
qos_profile: QosProfile,
) -> Result<impl Stream<Item = WrappedNativeMsg<T>> + Unpin>where
T: WrappedTypesupport + 'static,
pub fn subscribe_native<T>(
&mut self,
topic: &str,
qos_profile: QosProfile,
) -> Result<impl Stream<Item = WrappedNativeMsg<T>> + Unpin>where
T: WrappedTypesupport + 'static,
Subscribe to a ROS topic.
This function returns a Stream
of ros messages without the rust convenience types.
sourcepub fn subscribe_untyped(
&mut self,
topic: &str,
topic_type: &str,
qos_profile: QosProfile,
) -> Result<impl Stream<Item = Result<Value>> + Unpin>
pub fn subscribe_untyped( &mut self, topic: &str, topic_type: &str, qos_profile: QosProfile, ) -> Result<impl Stream<Item = Result<Value>> + Unpin>
Subscribe to a ROS topic.
This function returns a Stream
of ros messages as serde_json::Value
:s.
Useful when you cannot know the type of the message at compile time.
sourcepub fn subscribe_raw(
&mut self,
topic: &str,
topic_type: &str,
qos_profile: QosProfile,
) -> Result<impl Stream<Item = Vec<u8>> + Unpin>
pub fn subscribe_raw( &mut self, topic: &str, topic_type: &str, qos_profile: QosProfile, ) -> Result<impl Stream<Item = Vec<u8>> + Unpin>
Subscribe to a ROS topic.
This function returns a Stream
of ros messages as non-deserialized Vec<u8>
:s.
Useful if you just want to pass the data along to another part of the system.
sourcepub fn create_service<T>(
&mut self,
service_name: &str,
qos_profile: QosProfile,
) -> Result<impl Stream<Item = ServiceRequest<T>> + Unpin>where
T: WrappedServiceTypeSupport + 'static,
pub fn create_service<T>(
&mut self,
service_name: &str,
qos_profile: QosProfile,
) -> Result<impl Stream<Item = ServiceRequest<T>> + Unpin>where
T: WrappedServiceTypeSupport + 'static,
Create a ROS service.
This function returns a Stream
of ServiceRequest
:s. Call
respond
on the Service Request to send the reply.
sourcepub fn create_client<T>(
&mut self,
service_name: &str,
qos_profile: QosProfile,
) -> Result<Client<T>>where
T: WrappedServiceTypeSupport + 'static,
pub fn create_client<T>(
&mut self,
service_name: &str,
qos_profile: QosProfile,
) -> Result<Client<T>>where
T: WrappedServiceTypeSupport + 'static,
Create a ROS service client.
A service client is used to make requests to a ROS service server.
sourcepub fn create_client_untyped(
&mut self,
service_name: &str,
service_type: &str,
qos_profile: QosProfile,
) -> Result<ClientUntyped>
pub fn create_client_untyped( &mut self, service_name: &str, service_type: &str, qos_profile: QosProfile, ) -> Result<ClientUntyped>
Create a ROS service client.
A service client is used to make requests to a ROS service
server. This function returns an UntypedClient
, which deals
with serde_json::Value
s instead of concrete types. Useful
when you cannot know the type of the message at compile time.
sourcepub fn is_available(
client: &dyn IsAvailablePollable,
) -> Result<impl Future<Output = Result<()>>>
pub fn is_available( client: &dyn IsAvailablePollable, ) -> Result<impl Future<Output = Result<()>>>
Register a client for wakeup when the service or action server is available to the node.
Returns a Future
that completes when the service/action server is available.
This function will register the client to be polled in
spin_once
until available, so spin_once must be called
repeatedly in order to get the wakeup.
sourcepub fn create_action_client<T>(
&mut self,
action_name: &str,
) -> Result<ActionClient<T>>where
T: WrappedActionTypeSupport + 'static,
pub fn create_action_client<T>(
&mut self,
action_name: &str,
) -> Result<ActionClient<T>>where
T: WrappedActionTypeSupport + 'static,
Create a ROS action client.
An action client is used to make requests to a ROS action server.
sourcepub fn create_action_client_untyped(
&mut self,
action_name: &str,
action_type: &str,
) -> Result<ActionClientUntyped>
pub fn create_action_client_untyped( &mut self, action_name: &str, action_type: &str, ) -> Result<ActionClientUntyped>
Create a ROS action client.
A action client is used to make requests to a ROS service
server. This function returns a ActionClientUntyped
, which deals
with serde_json::Value
s instead of concrete types. Useful
when you cannot know the type of the message at compile time.
sourcepub fn create_action_server<T>(
&mut self,
action_name: &str,
) -> Result<impl Stream<Item = ActionServerGoalRequest<T>> + Unpin>where
T: WrappedActionTypeSupport + 'static,
pub fn create_action_server<T>(
&mut self,
action_name: &str,
) -> Result<impl Stream<Item = ActionServerGoalRequest<T>> + Unpin>where
T: WrappedActionTypeSupport + 'static,
Create a ROS action server.
This function returns a stream of GoalRequest
s, which needs
to be either accepted or rejected.
sourcepub fn create_publisher<T>(
&mut self,
topic: &str,
qos_profile: QosProfile,
) -> Result<Publisher<T>>where
T: WrappedTypesupport,
pub fn create_publisher<T>(
&mut self,
topic: &str,
qos_profile: QosProfile,
) -> Result<Publisher<T>>where
T: WrappedTypesupport,
Create a ROS publisher.
sourcepub fn create_publisher_untyped(
&mut self,
topic: &str,
topic_type: &str,
qos_profile: QosProfile,
) -> Result<PublisherUntyped>
pub fn create_publisher_untyped( &mut self, topic: &str, topic_type: &str, qos_profile: QosProfile, ) -> Result<PublisherUntyped>
Create a ROS publisher with a type given at runtime, where the data may either be
supplied as JSON (using the publish
method) or a pre-serialized ROS message
(i.e. &u8, using the publish_raw
method).
sourcepub fn destroy_publisher<T: WrappedTypesupport>(&mut self, p: Publisher<T>)
pub fn destroy_publisher<T: WrappedTypesupport>(&mut self, p: Publisher<T>)
Destroy a ROS publisher.
sourcepub fn destroy_publisher_untyped(&mut self, p: PublisherUntyped)
pub fn destroy_publisher_untyped(&mut self, p: PublisherUntyped)
Destroy a ROS publisher.
sourcepub fn spin_once(&mut self, timeout: Duration)
pub fn spin_once(&mut self, timeout: Duration)
Spin the ROS node.
This handles wakeups of all subscribes, services, etc on the ros side. In turn, this will complete future and wake up streams on the rust side. This needs to be called repeatedly (see the examples).
timeout
is a duration specifying how long the spin should
block for if there are no pending events.
sourcepub fn get_topic_names_and_types(&self) -> Result<HashMap<String, Vec<String>>>
pub fn get_topic_names_and_types(&self) -> Result<HashMap<String, Vec<String>>>
Returns a map of topic names and type names of the publishers visible to this node.
pub fn get_publishers_info_by_topic( &self, topic_name: &str, no_mangle: bool, ) -> Result<Vec<TopicEndpointInfo>>
sourcepub fn create_wall_timer(&mut self, period: Duration) -> Result<Timer>
pub fn create_wall_timer(&mut self, period: Duration) -> Result<Timer>
Create a ROS wall timer.
Create a ROS timer that is woken up by spin every period
.
This timer uses ClockType::SteadyTime
clock.
sourcepub fn create_timer(&mut self, period: Duration) -> Result<Timer>
pub fn create_timer(&mut self, period: Duration) -> Result<Timer>
Create a ROS timer
Create a ROS timer that is woken up by spin every period
.
This timer uses node’s ClockType::RosTime
clock.
sourcepub fn get_time_source(&self) -> TimeSource
pub fn get_time_source(&self) -> TimeSource
Get TimeSource of the node
See: TimeSource
sourcepub fn get_ros_clock(&self) -> Arc<Mutex<Clock>>
pub fn get_ros_clock(&self) -> Arc<Mutex<Clock>>
Get ROS clock of the node
This is the same clock that is used by ROS timers created in Node::create_timer
.
Trait Implementations§
Auto Trait Implementations§
impl Freeze for Node
impl !RefUnwindSafe for Node
impl !Sync for Node
impl Unpin for Node
impl !UnwindSafe for Node
Blanket Implementations§
source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
source§impl<T> IntoEither for T
impl<T> IntoEither for T
source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
self
into a Left
variant of Either<Self, Self>
if into_left
is true
.
Converts self
into a Right
variant of Either<Self, Self>
otherwise. Read moresource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
self
into a Left
variant of Either<Self, Self>
if into_left(&self)
returns true
.
Converts self
into a Right
variant of Either<Self, Self>
otherwise. Read more