Class Node

Class Documentation

class Node

Agnocast-only node. Drop-in replacement for rclcpp::Node in pure-Agnocast processes.

Public Types

using SharedPtr = std::shared_ptr<Node>
using ParameterValue = rclcpp::ParameterValue
using OnSetParametersCallbackHandle = rclcpp::node_interfaces::OnSetParametersCallbackHandle
using OnSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType

Public Functions

explicit AGNOCAST_PUBLIC Node(const std::string &node_name, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Construct a node with the given name.

Parameters:
  • node_name – Name of the node.

  • optionsNode options.

explicit AGNOCAST_PUBLIC Node(const std::string &node_name, const std::string &namespace_, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Construct a node with the given name and namespace.

Parameters:
  • node_name – Name of the node.

  • namespace_ – Namespace of the node.

  • optionsNode options.

inline AGNOCAST_PUBLIC std::string get_name () const

Return the name of the node.

Returns:

Node name.

inline AGNOCAST_PUBLIC rclcpp::Logger get_logger () const

Return the logger associated with this node.

Returns:

Logger instance.

inline AGNOCAST_PUBLIC std::string get_namespace () const

Return the namespace of the node.

Returns:

Node namespace.

inline AGNOCAST_PUBLIC std::string get_fully_qualified_name () const

Return the fully qualified name (namespace + node name).

Returns:

Fully qualified name string.

inline AGNOCAST_PUBLIC rclcpp::CallbackGroup::SharedPtr create_callback_group (rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node=true)

Create a callback group.

Parameters:
  • group_type – Type of callback group.

  • automatically_add_to_executor_with_node – Whether to auto-add to executor.

Returns:

Shared pointer to the created callback group.

inline AGNOCAST_PUBLIC void for_each_callback_group (const rclcpp::node_interfaces::NodeBaseInterface::CallbackGroupFunction &func)

Iterate over all callback groups, invoking the given function on each.

inline rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
inline rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
inline rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
inline rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
inline rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
inline rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
inline rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
inline AGNOCAST_PUBLIC const ParameterValue & declare_parameter (const std::string &name, const ParameterValue &default_value, const ParameterDescriptor &descriptor=ParameterDescriptor{}, bool ignore_override=false)

Declare a parameter with a default value.

Parameters:
  • name – Parameter name.

  • default_value – Default value.

  • descriptor – Optional descriptor.

  • ignore_override – If true, ignore launch-file overrides.

Returns:

The parameter value.

inline AGNOCAST_PUBLIC const ParameterValue & declare_parameter (const std::string &name, rclcpp::ParameterType type, const ParameterDescriptor &descriptor=ParameterDescriptor{}, bool ignore_override=false)

Declare a parameter with a given type (no default value).

Parameters:
  • name – Parameter name.

  • type – Parameter type.

  • descriptor – Optional descriptor.

  • ignore_override – If true, ignore launch-file overrides.

Returns:

The parameter value.

template<typename ParameterT>
inline AGNOCAST_PUBLIC auto declare_parameter(const std::string &name, const ParameterT &default_value, const ParameterDescriptor &descriptor = ParameterDescriptor{}, bool ignore_override = false)

Declare a parameter with a typed default value.

Template Parameters:

ParameterT – C++ type of the parameter.

Parameters:
  • name – Parameter name.

  • default_value – Default value.

  • descriptor – Optional descriptor.

  • ignore_override – If true, ignore launch-file overrides.

Returns:

The parameter value.

template<typename ParameterT>
inline AGNOCAST_PUBLIC auto declare_parameter(const std::string &name, const ParameterDescriptor &descriptor = ParameterDescriptor{}, bool ignore_override = false)

Declare a parameter using only its type (default-constructed).

Template Parameters:

ParameterT – C++ type of the parameter.

Parameters:
  • name – Parameter name.

  • descriptor – Optional descriptor.

  • ignore_override – If true, ignore launch-file overrides.

Returns:

The parameter value.

inline AGNOCAST_PUBLIC bool has_parameter (const std::string &name) const

Check whether a parameter has been declared.

Returns:

True if the parameter exists.

inline AGNOCAST_PUBLIC void undeclare_parameter (const std::string &name)

Undeclare a previously declared parameter.

inline AGNOCAST_PUBLIC rclcpp::Parameter get_parameter (const std::string &name) const

Get a parameter by name.

Returns:

The requested parameter.

inline AGNOCAST_PUBLIC bool get_parameter (const std::string &name, rclcpp::Parameter &parameter) const

Get a parameter by name, returning success status via bool.

Returns:

True if the parameter was found.

template<typename ParameterT> inline AGNOCAST_PUBLIC bool get_parameter (const std::string &name, ParameterT &parameter) const

Get a parameter and extract its typed value.

Template Parameters:

ParameterT – C++ type to extract.

Returns:

True if the parameter was found.

inline AGNOCAST_PUBLIC std::vector< rclcpp::Parameter > get_parameters (const std::vector< std::string > &names) const

Get multiple parameters by name.

Returns:

Vector of requested parameters.

template<typename ParameterT> inline AGNOCAST_PUBLIC bool get_parameters (const std::string &prefix, std::map< std::string, ParameterT > &values) const

Get parameters matching a prefix into a typed map.

Template Parameters:

ParameterT – C++ type to extract.

Returns:

True if any parameters matched the prefix.

inline AGNOCAST_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameter (const rclcpp::Parameter &parameter)

Set a single parameter.

Returns:

Result of the set operation.

inline AGNOCAST_PUBLIC std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters (const std::vector< rclcpp::Parameter > &parameters)

Set multiple parameters, one at a time.

Returns:

Vector of results.

inline AGNOCAST_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically (const std::vector< rclcpp::Parameter > &parameters)

Set multiple parameters atomically (all-or-nothing).

Returns:

Result of the atomic operation.

inline AGNOCAST_PUBLIC rcl_interfaces::msg::ParameterDescriptor describe_parameter (const std::string &name) const

Describe a single parameter.

Returns:

Parameter descriptor.

inline AGNOCAST_PUBLIC std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters (const std::vector< std::string > &names) const

Describe multiple parameters.

Returns:

Vector of parameter descriptors.

inline AGNOCAST_PUBLIC std::vector< uint8_t > get_parameter_types (const std::vector< std::string > &names) const

Get the types of the given parameters.

Returns:

Vector of parameter type identifiers.

inline AGNOCAST_PUBLIC rcl_interfaces::msg::ListParametersResult list_parameters (const std::vector< std::string > &prefixes, uint64_t depth) const

List parameters matching the given prefixes up to the given depth.

Returns:

Matching parameter names and prefixes.

inline AGNOCAST_PUBLIC rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback (OnSetParametersCallbackType callback)

Register a callback invoked before parameters are set.

Returns:

Handle to the registered callback.

inline AGNOCAST_PUBLIC void remove_on_set_parameters_callback (const rclcpp::node_interfaces::OnSetParametersCallbackHandle *const handler)

Remove a previously registered on-set-parameters callback.

inline AGNOCAST_PUBLIC rclcpp::Clock::SharedPtr get_clock ()

Get the clock used by this node.

Returns:

Shared pointer to the clock.

inline AGNOCAST_PUBLIC rclcpp::Clock::ConstSharedPtr get_clock () const

Get the clock used by this node (const).

Returns:

Shared pointer to the clock.

inline AGNOCAST_PUBLIC rclcpp::Time now () const

Return the current time according to this node’s clock.

Returns:

Current time.

inline AGNOCAST_PUBLIC size_t count_publishers (const std::string &topic_name) const

Return the number of publishers on a topic.

Returns:

Publisher count.

inline AGNOCAST_PUBLIC size_t count_subscribers (const std::string &topic_name) const

Return the number of subscribers on a topic.

Returns:

Subscriber count.

template<typename MessageT> inline AGNOCAST_PUBLIC agnocast::Publisher< MessageT >::SharedPtr create_publisher (const std::string &topic_name, const rclcpp::QoS &qos, agnocast::PublisherOptions options=agnocast::PublisherOptions{})

Create a publisher (QoS overload).

Template Parameters:

MessageT – ROS message type.

Parameters:
  • topic_name – Topic name.

  • qos – Quality of service profile.

  • options – Publisher options.

Returns:

Shared pointer to the created publisher.

template<typename MessageT> inline AGNOCAST_PUBLIC agnocast::Publisher< MessageT >::SharedPtr create_publisher (const std::string &topic_name, size_t queue_size, agnocast::PublisherOptions options=agnocast::PublisherOptions{})

Create a publisher (queue-size overload).

Template Parameters:

MessageT – ROS message type.

Parameters:
  • topic_name – Topic name.

  • queue_size – History depth for the QoS profile.

  • options – Publisher options.

Returns:

Shared pointer to the created publisher.

template<typename MessageT, typename Func> inline AGNOCAST_PUBLIC agnocast::Subscription< MessageT >::SharedPtr create_subscription (const std::string &topic_name, const rclcpp::QoS &qos, Func &&callback, agnocast::SubscriptionOptions options=agnocast::SubscriptionOptions{})

Create a subscription (QoS overload).

Template Parameters:
  • MessageT – ROS message type.

  • Func – Callback type.

Parameters:
  • topic_name – Topic name.

  • qos – Quality of service profile.

  • callback – Callback invoked on each received message.

  • options – Subscription options.

Returns:

Shared pointer to the created subscription.

template<typename MessageT, typename Func> inline AGNOCAST_PUBLIC agnocast::Subscription< MessageT >::SharedPtr create_subscription (const std::string &topic_name, size_t queue_size, Func &&callback, agnocast::SubscriptionOptions options=agnocast::SubscriptionOptions{})

Create a subscription (queue-size overload).

Template Parameters:
  • MessageT – ROS message type.

  • Func – Callback type.

Parameters:
  • topic_name – Topic name.

  • queue_size – History depth for the QoS profile.

  • callback – Callback invoked on each received message.

  • options – Subscription options.

Returns:

Shared pointer to the created subscription.

template<typename MessageT> inline AGNOCAST_PUBLIC agnocast::PollingSubscriber< MessageT >::SharedPtr create_subscription (const std::string &topic_name, const size_t qos_history_depth)

Create a polling subscription (history-depth overload).

Template Parameters:

MessageT – ROS message type.

Parameters:
  • topic_name – Topic name.

  • qos_history_depth – History depth for the QoS profile.

Returns:

Shared pointer to the created polling subscription.

template<typename MessageT> inline AGNOCAST_PUBLIC agnocast::PollingSubscriber< MessageT >::SharedPtr create_subscription (const std::string &topic_name, const rclcpp::QoS &qos)

Create a polling subscription (QoS overload).

Template Parameters:

MessageT – ROS message type.

Parameters:
  • topic_name – Topic name.

  • qos – Quality of service profile.

Returns:

Shared pointer to the created polling subscription.

template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT> inline AGNOCAST_PUBLIC WallTimer< CallbackT >::SharedPtr create_wall_timer (std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr, bool autostart=true)

Create a wall timer.

Parameters:
  • period – Timer period.

  • callback – Callback invoked on each tick.

  • group – Callback group (nullptr = default).

  • autostart – Whether to start immediately (not yet supported; always true).

Returns:

Shared pointer to the created timer.

template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT> inline AGNOCAST_PUBLIC GenericTimer< CallbackT >::SharedPtr create_timer (std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr, bool autostart=true)

Create a timer using the node’s clock.

Parameters:
  • period – Timer period.

  • callback – Callback invoked on each tick.

  • group – Callback group (nullptr = default).

  • autostart – Whether to start immediately (not yet supported; always true).

Returns:

Shared pointer to the created timer.

template<typename DurationRepT, typename DurationT, typename CallbackT>
inline GenericTimer<CallbackT>::SharedPtr create_timer(std::chrono::duration<DurationRepT, DurationT> period, CallbackT &&callback, rclcpp::CallbackGroup::SharedPtr group, rclcpp::Clock::SharedPtr clock)
template<typename ServiceT>
inline agnocast::Client<ServiceT>::SharedPtr create_client(const std::string &service_name, const rclcpp::QoS &qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create a service client.

Parameters:
  • service_nameService name.

  • qos – Quality of service profile.

  • group – Callback group (nullptr = default).

Returns:

Shared pointer to the created client.

template<typename ServiceT, typename Func>
inline agnocast::Service<ServiceT>::SharedPtr create_service(const std::string &service_name, Func &&callback, const rclcpp::QoS &qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create a service server.

Template Parameters:

Func

Callable with signature void(const agnocast::ipc_shared_ptr<const RequestT>&,

agnocast::ipc_shared_ptr<ResponseT>&).

Parameters:
  • service_nameService name.

  • callback – Callback invoked on each request.

  • qos – Quality of service profile.

  • group – Callback group (nullptr = default).

Returns:

Shared pointer to the created service.