Free Functions (Stage 1)
These free functions are used with rclcpp::Node at Stage 1. Pass the node pointer as the first argument.
create_publisher()
agnocast::Publisher<MessageT>::SharedPtr create_publisher(NodeT *node, const std::string &topic_name, const rclcpp::QoS &qos, const agnocast::PublisherOptions &options)
Create an Agnocast publisher (Stage 1 free function, QoS overload).
| Template Parameter |
Description |
MessageT |
ROS message type. |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
topic_name |
— |
Topic name. |
qos |
— |
Quality of service profile. |
options |
agnocast::PublisherOptions{} |
Publisher options. |
|
|
| Returns |
Shared pointer to the created publisher. |
create_publisher() [overload 2]
agnocast::Publisher<MessageT>::SharedPtr create_publisher(NodeT *node, const std::string &topic_name, const size_t qos_history_depth, const agnocast::PublisherOptions &options)
Create an Agnocast publisher (Stage 1 free function, history-depth overload).
| Template Parameter |
Description |
MessageT |
ROS message type. |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
topic_name |
— |
Topic name. |
qos_history_depth |
— |
History depth for the QoS profile. |
options |
agnocast::PublisherOptions{} |
Publisher options. |
|
|
| Returns |
Shared pointer to the created publisher. |
create_generic_publisher()
GenericPublisher::SharedPtr create_generic_publisher(NodeT *node, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, agnocast::PublisherOptions options)
Create an Agnocast generic publisher (Stage 1 free function, QoS overload).
| Template Parameter |
Description |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
topic_name |
— |
Topic name. |
topic_type |
— |
Message type string. |
qos |
— |
Quality of service profile. |
options |
agnocast::PublisherOptions{} |
Publisher options. |
|
|
| Returns |
Shared pointer to the created generic publisher. |
create_generic_publisher() [overload 2]
GenericPublisher::SharedPtr create_generic_publisher(NodeT *node, const std::string &topic_name, const std::string &topic_type, const size_t qos_history_depth, agnocast::PublisherOptions options)
Create an Agnocast generic publisher (Stage 1 free function, history-depth overload).
| Template Parameter |
Description |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
topic_name |
— |
Topic name. |
topic_type |
— |
Message type string. |
qos_history_depth |
— |
History depth for the QoS profile. |
options |
agnocast::PublisherOptions{} |
Publisher options. |
|
|
| Returns |
Shared pointer to the created generic publisher. |
create_subscription()
agnocast::Subscription<MessageT>::SharedPtr create_subscription(NodeT *node, const std::string &topic_name, const rclcpp::QoS &qos, Func &&callback, agnocast::SubscriptionOptions options)
Create an Agnocast subscription (Stage 1 free function, QoS overload).
| Template Parameter |
Description |
MessageT |
ROS message type. |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
Func |
Callback callable with void(agnocast::ipc_shared_ptr<const MessageT>&&). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
topic_name |
— |
Topic name. |
qos |
— |
Quality of service profile. |
callback |
— |
Callback invoked on each received message. |
options |
agnocast::SubscriptionOptions{} |
Subscription options. |
|
|
| Returns |
Shared pointer to the created subscription. |
create_subscription() [overload 2]
agnocast::Subscription<MessageT>::SharedPtr create_subscription(NodeT *node, const std::string &topic_name, const size_t qos_history_depth, Func &&callback, agnocast::SubscriptionOptions options)
Create an Agnocast subscription (Stage 1 free function, history-depth overload).
| Template Parameter |
Description |
MessageT |
ROS message type. |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
Func |
Callback callable with void(agnocast::ipc_shared_ptr<const MessageT>&&). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
topic_name |
— |
Topic name. |
qos_history_depth |
— |
History depth for the QoS profile. |
callback |
— |
Callback invoked on each received message. |
options |
agnocast::SubscriptionOptions{} |
Subscription options. |
|
|
| Returns |
Shared pointer to the created subscription. |
create_subscription() [overload 3]
agnocast::PollingSubscriber<MessageT>::SharedPtr create_subscription(NodeT *node, const std::string &topic_name, const size_t qos_history_depth)
Create an Agnocast polling subscription (Stage 1 free function, history-depth overload).
| Template Parameter |
Description |
MessageT |
ROS message type. |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
| Parameter |
Description |
node |
Pointer to the node. |
topic_name |
Topic name. |
qos_history_depth |
History depth for the QoS profile. |
|
|
| Returns |
Shared pointer to the created polling subscription. |
create_subscription() [overload 4]
agnocast::PollingSubscriber<MessageT>::SharedPtr create_subscription(NodeT *node, const std::string &topic_name, const rclcpp::QoS &qos)
Create an Agnocast polling subscription (Stage 1 free function, QoS overload).
| Template Parameter |
Description |
MessageT |
ROS message type. |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
| Parameter |
Description |
node |
Pointer to the node. |
topic_name |
Topic name. |
qos |
Quality of service profile. |
|
|
| Returns |
Shared pointer to the created polling subscription. |
create_generic_subscription()
GenericSubscription::SharedPtr create_generic_subscription(NodeT *node, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, Func &&callback, agnocast::SubscriptionOptions options)
Create an Agnocast generic subscription (Stage 1 free function, QoS overload).
| Template Parameter |
Description |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
Func |
Callable accepting a serialized message, e.g. void(std::shared_ptr<const rclcpp::SerializedMessage>). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
topic_name |
— |
Topic name. |
topic_type |
— |
Message type string. |
qos |
— |
Quality of service profile. |
callback |
— |
Callback invoked on each received message. |
options |
agnocast::SubscriptionOptions{} |
Subscription options. |
|
|
| Returns |
Shared pointer to the created generic subscription. |
create_generic_subscription() [overload 2]
GenericSubscription::SharedPtr create_generic_subscription(NodeT *node, const std::string &topic_name, const std::string &topic_type, const size_t qos_history_depth, Func &&callback, agnocast::SubscriptionOptions options)
Create an Agnocast generic subscription (Stage 1 free function, history-depth overload).
| Template Parameter |
Description |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
Func |
Callable accepting a serialized message, e.g. void(std::shared_ptr<const rclcpp::SerializedMessage>). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
topic_name |
— |
Topic name. |
topic_type |
— |
Message type string. |
qos_history_depth |
— |
History depth for the QoS profile. |
callback |
— |
Callback invoked on each received message. |
options |
agnocast::SubscriptionOptions{} |
Subscription options. |
|
|
| Returns |
Shared pointer to the created generic subscription. |
create_client()
agnocast::Client<ServiceT>::SharedPtr create_client(NodeT *node, const std::string &service_name, const rclcpp::QoS &qos, rclcpp::CallbackGroup::SharedPtr group)
Create an Agnocast service client (Stage 1 free function).
| Template Parameter |
Description |
ServiceT |
ROS service type. |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
service_name |
— |
Service name. |
qos |
rclcpp::ServicesQoS() |
Quality of service profile. Defaults to rclcpp::ServicesQoS(). |
group |
nullptr |
Callback group. Defaults to nullptr (default callback group). |
|
|
| Returns |
Shared pointer to the created client. |
create_service()
agnocast::Service<ServiceT>::SharedPtr create_service(NodeT *node, const std::string &service_name, Func &&callback, const rclcpp::QoS &qos, rclcpp::CallbackGroup::SharedPtr group)
Create an Agnocast service server (Stage 1 free function).
| Template Parameter |
Description |
ServiceT |
ROS service type. |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
Func |
Callable that takes ipc_shared_ptr and ipc_shared_ptr (const&, &&, or by-value) (return value ignored). |
| Parameter |
Default |
Description |
node |
— |
Pointer to the node. |
service_name |
— |
Service name. |
callback |
— |
Callback invoked on each request. |
qos |
rclcpp::ServicesQoS() |
Quality of service profile. Defaults to rclcpp::ServicesQoS(). |
group |
nullptr |
Callback group. Defaults to nullptr (default callback group). |
|
|
| Returns |
Shared pointer to the created service. |
create_timer()
agnocast::TimerBase::SharedPtr create_timer(NodeT node, rclcpp::Clock::SharedPtr clock, rclcpp::Duration period, CallbackT &&callback, rclcpp::CallbackGroup::SharedPtr group, bool autostart)
Create a timer with a given clock. This free function mirrors the rclcpp::create_timer() API for portability.
| Template Parameter |
Description |
NodeT |
Node type (rclcpp::Node or agnocast::Node). |
CallbackT |
Callable type for the callback. |
| Parameter |
Default |
Description |
node |
— |
Node providing get_node_base_interface() for the default callback group. |
clock |
— |
Clock to drive the timer. |
period |
— |
Time interval between triggers of the callback. |
callback |
— |
User-defined callback function. |
group |
nullptr |
Callback group to execute this timer's callback in. |
autostart |
true |
Whether to start the timer immediately (not yet supported; always true). |
|
|
| Returns |
Shared pointer to the created timer. |
init()
void init(int argc, char const *const *argv)
Initialize Agnocast. Must be called once before creating any agnocast::Node. This is the counterpart of rclcpp::init() for agnocast::Node.
| Parameter |
Description |
argc |
Number of command-line arguments. |
argv |
Command-line argument array. |
shutdown()
Shut down Agnocast. Should be called before process exit in agnocast::Node processes. This is the counterpart of rclcpp::shutdown() for agnocast::Node.
ok()
Check whether Agnocast context is valid (initialized and not shutdown). This is the counterpart of rclcpp::ok() for agnocast::Node.