The ICEY Context#
The ICEY context is initialized by providing a node and provides a Node-like API
-
class Context : public icey::ContextAsyncAwait, public std::enable_shared_from_this<Context>, private boost::noncopyable#
The context is what is returned when calling
node->icey()
(NodeWithIceyContext::icey). It provides an new node-like API for creating ROS entities, these entities are however streams.Public Types
-
using FValidate = std::function<std::string(const rclcpp::Parameter&)>#
The parameter validation function that allows the parameter update if the returned error string is empty (i.e. “”) and rejects it otherwise with this non-empty error string.
Public Functions
-
template<class NodeT>
explicit Context(NodeT *node)# Constructs the Context from the given node pointer. Supports both rclcpp::Node as well as a lifecycle node.
- Parameters:
node – the node
- Template Parameters:
NodeT – rclcpp::Node or rclcpp_lifecycle::LifecycleNode
-
template<class ParameterT>
ParameterStream<ParameterT> declare_parameter(const std::string ¶meter_name, const ParameterT &default_value, const Validator<ParameterT> &validator = {}, std::string description = "", bool read_only = false, bool ignore_override = false)# Declares a single parameter to ROS and register for updates. The ParameterDescriptor is created automatically matching the given Validator.
- Template Parameters:
ParameterT – The type of the parameter. ROS actually allows for type changes at runtime but we do not want that.
- Parameters:
parameter_name – name
default_value – Every parameter must be initialized, this value will be used for this.
validator – A validator constraints the parameter to certain values if provided
description – Optionally, a description of the parameter may be provided
read_only – If set to true, parameter updates at runtime will be rejected
ignore_override – See rclcpp::Node::declare_parameter documentation
-
template<class ParameterStruct>
void declare_parameter_struct(ParameterStruct ¶ms, const std::function<void(const std::string&)> ¬ify_callback = {}, std::string name_prefix = "")# Declare a given parameter struct to ROS.
Example usage:
/// Here you declare in a single struct all parameters of the node: struct NodeParameters { /// We can have regular fields : double amplitude{3}; /// And as well parameters with constraints and a description: icey::Parameter<double> frequency{10., icey::Interval(0., 25.), std::string("The frequency of the sine")}; icey::Parameter<std::string> mode{"single", icey::Set<std::string>({"single", "double", "pulse"})}; /// We can also have nested structs with more parameters, they will be named others.max_amp, others.cov: struct OtherParams { double max_amp = 6.; std::vector<double> cov; } others; }; class MyNode : public icey::Node { MyNode(std::string name): icey::Node(name) { /// Now simply declare the parameter struct and a callback that is called when any field updates: this->icey().declare_parameter_struct(params_, [&](const std::string &changed_parameter) { RCLCPP_INFO_STREAM(node->get_logger(), "Parameter " << changed_parameter << " changed"); }); } // Hold the parameter struct inside the class: NodeParameters params_; };
Note
The passed parameter struct object
params
must have the same lifetime as the node, so it’s best is to store it as a member of the node class.- Template Parameters:
ParameterStruct – the type of the parameter struct. It must be a struct/class with fields of either a primitive type supported by ROS (e.g.
double
) or aicey::Parameter
, or another (nested) struct with more such fields.- Parameters:
params – The parameter struct object where the values will be written to.
notify_callback – The callback that gets called when any field changes (optional)
name_prefix – Prefix for each parameter (optional). Used by the recursive call to support nested structs.
-
template<class MessageT>
SubscriptionStream<MessageT> create_subscription(const std::string &name, const rclcpp::QoS &qos = rclcpp::SystemDefaultsQoS(), const rclcpp::SubscriptionOptions &options = rclcpp::SubscriptionOptions())# Create a subscription stream. Works otherwise the same as [rclcpp::Node::create_subscription].
-
template<class MessageT, class Callback>
SubscriptionStream<MessageT> create_subscription(const std::string &name, Callback &&cb, const rclcpp::QoS &qos = rclcpp::SystemDefaultsQoS(), const rclcpp::SubscriptionOptions &options = rclcpp::SubscriptionOptions())# Create a subscription stream and registers the given callback. The callback can be either synchronous or asynchronous. Works otherwise the same as [rclcpp::Node::create_subscription].
-
TimerStream create_timer(const Duration &period, bool is_one_off_timer = false)#
Create a timer stream. The Stream yields as a value the total number of ticks.
- Parameters:
period – the period time
is_one_off_timer – if set to true, this timer will execute only once. Works otherwise the same as [rclcpp::Node::create_timer].
-
template<class Callback>
TimerStream create_timer(const Duration &period, Callback cb, bool is_one_off_timer = false)# Create a timer and register a callback.
- Parameters:
period – the period time
is_one_off_timer – if set to true, this timer will execute only once. Works otherwise the same as [rclcpp::Node::create_timer].
-
TransformSubscriptionStream create_transform_subscription(ValueOrParameter<std::string> target_frame, ValueOrParameter<std::string> source_frame)#
Create a subscription that subscribes to a single transform between two frames. This stream will emit a value every time the transform between these two frames changes, i.e. it is a stream. If you need to lookup transforms at a specific point in time, look instead at
Context::create_transform_buffer
.
-
template<class Message>
PublisherStream<Message> create_publisher(const std::string &topic_name, const rclcpp::QoS &qos = rclcpp::SystemDefaultsQoS(), const rclcpp::PublisherOptions publisher_options = {})# Create a publisher stream. Works otherwise the same as [rclcpp::Node::create_publisher].
-
TransformPublisherStream create_transform_publisher()#
Create a publisher to publish transforms on the
/tf
topic. Works otherwise the same as [tf2_ros::TransformBroadcaster].
-
template<class ParameterT, class CallbackT>
auto add_parameter(const std::string &name, const ParameterT &default_value, CallbackT &&update_callback, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor = {}, FValidate f_validate = {}, bool ignore_override = false)# Declares a parameter and registers a validator callback and a callback that will get called when the parameters updates.
-
template<class OnTransform, class OnError>
void add_tf_subscription(GetValue<std::string> target_frame, GetValue<std::string> source_frame, OnTransform &&on_transform, OnError &&on_error)# Subscribe to a transform on tf between two frames.
-
auto add_tf_broadcaster_if_needed()#
-
template<AnyStream S, class ...Args>
S create_stream(Args&&... args)# Creates a new stream of type S by passing the args to the constructor. It adds the impl to the list of streams so that it does not go out of scope. It also sets the context.
-
template<class StreamImpl>
Weak<StreamImpl> create_stream_impl()# Creates a new stream impl and adds it to the list of stream impls so that it does not go out of scope.
-
using FValidate = std::function<std::string(const rclcpp::Parameter&)>#
If you only want async/await:
-
class ContextAsyncAwait : public icey::NodeBase#
A context that provides only async/await related entities.
Subclassed by icey::Context
Public Functions
-
ContextAsyncAwait(const ContextAsyncAwait&) = delete#
-
ContextAsyncAwait(ContextAsyncAwait&&) = delete#
-
ContextAsyncAwait &operator=(const ContextAsyncAwait&) = delete#
-
ContextAsyncAwait &operator=(ContextAsyncAwait&&) = delete#
-
template<class NodeT>
explicit ContextAsyncAwait(NodeT *node)# Constructs the Context from the given node pointer. Supports both rclcpp::Node as well as a lifecycle node.
- Parameters:
node – the node
- Template Parameters:
NodeT – rclcpp::Node or rclcpp_lifecycle::LifecycleNode
Create a subscription and registers the given callback. The callback can be either synchronous or asynchronous. Works otherwise the same as [rclcpp::Node::create_subscription].
Create a timer that accepts asynchronous callbacks (i.e. coroutines)
Note
This function creates a wall-clock timer.
Note
A callback signature that accepts a TimerInfo argument is not implemented yet Works otherwise the same as [rclcpp::Node::create_timer].
- Parameters:
period – the period time
callback – the callback, may be synchronous or asynchronous
- Template Parameters:
Callback – () -> void or () -> impl::Promise<void>
Create a service server supporting asynchronous callbacks (i.e. coroutines). One a request is received, the provided callback will be called. This callback receives the request and returns a shared pointer to the response. If it returns a nullptr, then no response is made. The callback can be either synchronous (a regular function) or asynchronous, i.e. a coroutine. The callbacks returns the response. The context additionally provdes bookkeeping for this service, this means you do not have to store service in the node class. Works otherwise the same as [rclcpp::Node::create_service].
- Parameters:
service_name – the name of the service
callback – the callback
qos – quality of service
- Template Parameters:
Callback – Either (std::shared_ptr<ServiceT::Request>) -> std::shared_ptr<ServiceT::Response> or (std::shared_ptr<ServiceT::Request>) -> icey::impl::Promise<std::shared_ptr<ServiceT::Response>>
-
template<class ServiceT>
ServiceClient<ServiceT> create_client(const std::string &service_name, const rclcpp::QoS &qos = rclcpp::ServicesQoS())# Create a service client that supports async/await. Works otherwise the same as [rclcpp::Node::create_client].
-
TransformBuffer create_transform_buffer()#
Creates a transform buffer that works like the usual combination of a tf2_ros::Buffer and a tf2_ros::TransformListener. It is used to
lookup()
transforms asynchronously at a specific point in time.
-
std::shared_ptr<TransformBufferImpl> add_tf_listener_if_needed()#
Public Members
-
std::shared_ptr<TransformBufferImpl> tf_buffer_impl_#
The TF async interface impl.
-
ContextAsyncAwait(const ContextAsyncAwait&) = delete#
Convenience node wrappers containing the Icey context
-
using icey::Node = NodeWithIceyContext<rclcpp::Node>#
The node type that you will use instead of an
rclcpp::Node
. It derives from therclcpp::Node
, so that you can do everything that you can also with anrclcpp::Node
. SeeNodeWithIceyContext
for details.
-
using icey::LifecycleNode = NodeWithIceyContext<rclcpp_lifecycle::LifecycleNode>#
The node type that you will use instead of an
rclcpp_lifecycle::LifecycleNode
. It derives from therclcpp_lifecycle::LifecycleNode
, so that you can do everything that you can also with anrclcpp_lifecycle::LifecycleNode
. SeeNodeWithIceyContext
for details.
-
template<class NodeType>
class NodeWithIceyContext : public NodeType# The ROS node, additionally owning the context that holds the Streams.
- Template Parameters:
NodeType – can either be rclcpp::Node or rclcpp_lifecycle::LifecycleNode
-
struct TransformBufferImpl#
A subscription + buffer for transforms that allows for asynchronous lookups and to subscribe on a single transform between two coordinate systems. It is otherwise implemented similarly to the tf2_ros::TransformListener but offering a well-developed asynchronous API. It works like this: Every time a new message is received on /tf, we check whether a It subscribes on the topic /tf and listens for relevant transforms (i.e. ones we subscribed to or the ones we requested a lookup). If any relevant transform was received, it notifies via a callback. It is therefore an asynchronous interface to TF.
Why not using
tf2_ros::AsyncBuffer
? Due to multiple issues with it. (1) It uses thestd::future/std::promise
primitives that are effectively useless. (2) tf2_ros::AsyncBuffer::waitFroTransform has a bug: We cannot make another lookup in the callback of a lookup (it holds a (non-reentrant) mutex locked while calling the user callback), making it impossible to chain asynchronous operations.See also
This class is used to implement the
TransformSubscriptionStream
and theTransformBuffer
.Public Types
-
using TransformMsg = geometry_msgs::msg::TransformStamped#
-
using TransformsMsg = tf2_msgs::msg::TFMessage::ConstSharedPtr#
-
using OnTransform = std::function<void(const TransformMsg&)>#
-
using OnError = std::function<void(const tf2::TransformException&)>#
-
using GetFrame = std::function<std::string()>#
-
using RequestHandle = std::shared_ptr<TransformRequest>#
A request for a transform lookup: It represents effectively a single call to the async_lookup function. Even if you call async_lookup with the exact same arguments (same frames and time), this will count as two separate requests.
Public Functions
-
TransformBufferImpl(const TransformBufferImpl&) = delete#
We make this class non-copyable since it captures the this-pointer in clojures.
-
TransformBufferImpl(TransformBufferImpl&&) = delete#
-
TransformBufferImpl &operator=(const TransformBufferImpl&) = delete#
-
TransformBufferImpl &operator=(TransformBufferImpl&&) = delete#
-
void add_subscription(const GetFrame &target_frame, const GetFrame &source_frame, const OnTransform &on_transform, const OnError &on_error)#
Subscribe to a single transform between two coordinate systems. Every time this transform changes, the
on_transform
callback function is called. More precisely, every time a message arrives on the/tf
or/tf_static
topic, a lookup is attempted. If the lookup fails,on_error
is called. If the lookup succeeds and if the looked up transform is.
-
Result<geometry_msgs::msg::TransformStamped, std::string> get_from_buffer(std::string target_frame, std::string source_frame, const Time &time) const#
Queries the TF buffer for a transform at the given time between the given frames. It does not wait but instead only returns something if the transform is already in the buffer.
- Parameters:
target_frame –
source_frame –
time –
- Returns:
The transform or the TF error if the transform is not in the buffer.
-
RequestHandle lookup(const std::string &target_frame, const std::string &source_frame, Time time, const Duration &timeout, OnTransform on_transform, OnError on_error)#
Makes an asynchronous lookup for a for a transform at the given time between the given frames. Callback-based API.
Warning
Currently the timeout is measured with wall-time, i.e. does not consider sim-time due to the limitation of ROS 2 Humble only offering wall-timers
- Parameters:
target_frame –
source_frame –
time –
timeout –
on_transform – The callback that is called with the requested transform after it becomes available
on_error – The callback that is called if a timeout occurs.
- Returns:
The “handle”, identifying this request. You can use this handle to call
cancel_request
if you want to cancel the request.
-
impl::Promise<geometry_msgs::msg::TransformStamped, std::string> lookup(const std::string &target_frame, const std::string &source_frame, const Time &time, const Duration &timeout)#
Does an asynchronous lookup for a single transform that can be awaited using
co_await
- Parameters:
target_frame –
source_frame –
time – At which time to get the transform
timeout – How long to wait for the transform
- Returns:
A future that resolves with the transform or with an error if a timeout occurs
-
impl::Promise<geometry_msgs::msg::TransformStamped, std::string> lookup(const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const Duration &timeout)#
Same as
lookup
, but accepts a ROS time point.- Parameters:
target_frame –
source_frame –
time – At which time to get the transform
timeout – How long to wait for the transform
- Returns:
A future that resolves with the transform or with an error if a timeout occurs
-
bool cancel_request(RequestHandle request)#
Cancel a transform request: This means that the registered callbacks will no longer be called. If the given request does not exist, this function does nothing.
Public Members
-
std::shared_ptr<tf2_ros::Buffer> buffer_#
We take a tf2_ros::Buffer instead of a tf2::BufferImpl only to be able to use ROS-time API (internally TF2 has it’s own timestamps…), not because we need to wait on anything (that’s what tf2_ros::Buffer does in addition to tf2::BufferImpl).
-
struct TransformRequest#
A transform request stores a request for looking up a transform between two coordinate systems. Either (1) at a particular time with a timeout, or (2) as a subscription. When “subscribing” to a transform, we yield a transform each time it changes.
Public Functions
-
using TransformMsg = geometry_msgs::msg::TransformStamped#
-
struct NodeBase#
A helper to abstract regular rclcpp::Nodes and LifecycleNodes. Similar to the NodeInterfaces class: ros2/rclcpp#2041 which doesn’t look like it’s going to come for Humble: ros2/rclcpp#2309
Subclassed by icey::ContextAsyncAwait
Public Functions
-
auto get_node_base_interface() const#
These getters are needed at some places like for the ParameterEventHandler. Other functions likely require this interface too.
-
auto get_node_graph_interface() const#
-
auto get_node_clock_interface() const#
-
auto get_node_logging_interface() const#
-
auto get_node_timers_interface() const#
-
auto get_node_topics_interface() const#
-
auto get_node_services_interface() const#
-
auto get_node_parameters_interface() const#
-
auto get_node_time_source_interface() const#
-
template<class T>
auto get_parameter(const std::string &name)#
-
template<class Msg, class F>
auto create_subscription(const std::string &topic, F &&cb, const rclcpp::QoS &qos, const rclcpp::SubscriptionOptions &options = {})#
-
template<class Msg>
auto create_publisher(const std::string &topic, const rclcpp::QoS &qos, const rclcpp::PublisherOptions publisher_options = {})#
-
bool is_regular_node()#
-
bool is_lifecycle_node()#
-
auto get_node_base_interface() const#