rclcpp  master
C++ ROS Client Library API
Namespaces | Classes | Typedefs | Enumerations | Functions
rclcpp Namespace Reference

This header provides the get_node_topics_interface() template function. More...

Namespaces

 allocator
 
 callback_group
 
 contexts
 
 detail
 
 exceptions
 
 executor
 
 executors
 
 function_traits
 
 graph_listener
 
 intra_process_manager
 
 mapped_ring_buffer
 
 memory_strategies
 
 memory_strategy
 
 message_memory_strategy
 
 node_interfaces
 
 strategies
 
 subscription_traits
 
 type_support
 

Classes

class  AnyServiceCallback
 
class  AnySubscriptionCallback
 
class  AsyncParametersClient
 
class  Client
 
class  ClientBase
 
class  Clock
 
class  Context
 Context which encapsulates shared state between nodes and other similar entities. More...
 
class  ContextAlreadyInitialized
 Thrown when init is called on an already initialized context. More...
 
class  Duration
 
class  Event
 
class  GenericRate
 
class  GenericTimer
 Generic timer. Periodically executes a user-specified callback. More...
 
class  InitOptions
 Encapsulation of options for initializing rclcpp. More...
 
class  JumpHandler
 
struct  KeepAll
 Use to initialize the QoS with the keep_all history setting. More...
 
struct  KeepLast
 Use to initialize the QoS with the keep_last history setting and the given depth. More...
 
class  Logger
 
class  Node
 Node is the single point of entry for creating publishers and subscribers. More...
 
class  NodeOptions
 Encapsulation of options for node initialization. More...
 
class  Parameter
 Structure to store an arbitrary parameter with templated get/set methods. More...
 
class  ParameterEventsFilter
 
class  ParameterEventsQoS
 
class  ParameterService
 
class  ParametersQoS
 
class  ParameterTypeException
 Indicate the parameter type does not match the expected type. More...
 
class  ParameterValue
 Store the type and value of a parameter. More...
 
class  Publisher
 A publisher publishes messages of any type to a topic. More...
 
class  PublisherBase
 
struct  PublisherEventCallbacks
 Contains callbacks for various types of events a Publisher can receive from the middleware. More...
 
struct  PublisherFactory
 Factory with functions used to create a MessageT specific PublisherT. More...
 
struct  PublisherOptionsBase
 Non-templated part of PublisherOptionsWithAllocator<Allocator>. More...
 
struct  PublisherOptionsWithAllocator
 Structure containing optional configuration for Publishers. More...
 
class  QoS
 Encapsulation of Quality of Service settings. More...
 
class  QOSEventHandler
 
class  QOSEventHandlerBase
 
struct  QoSInitialization
 QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead. More...
 
class  RateBase
 
struct  ScopeExit
 
class  SensorDataQoS
 
class  Service
 
class  ServiceBase
 
class  ServicesQoS
 
class  Subscription
 Subscription implementation, templated on the type of message this subscription receives. More...
 
class  SubscriptionBase
 
struct  SubscriptionEventCallbacks
 Contains callbacks for non-message events that a Subscription can receive from the middleware. More...
 
struct  SubscriptionFactory
 Factory with functions used to create a Subscription<MessageT>. More...
 
struct  SubscriptionOptionsBase
 Non-template base class for subscription options. More...
 
struct  SubscriptionOptionsWithAllocator
 Structure containing optional configuration for Subscriptions. More...
 
class  SyncParametersClient
 
class  SystemDefaultsQoS
 
class  Time
 
class  TimerBase
 
class  TimeSource
 
class  Waitable
 
class  WallTimer
 

Typedefs

using ParameterMap = std::unordered_map< std::string, std::vector< Parameter > >
 A map of fully qualified node names to a list of parameters. More...
 
using PublisherOptions = PublisherOptionsWithAllocator< std::allocator< void > >
 
using QOSDeadlineRequestedInfo = rmw_requested_deadline_missed_status_t
 
using QOSDeadlineOfferedInfo = rmw_offered_deadline_missed_status_t
 
using QOSLivelinessChangedInfo = rmw_liveliness_changed_status_t
 
using QOSLivelinessLostInfo = rmw_liveliness_lost_status_t
 
using QOSDeadlineRequestedCallbackType = std::function< void(QOSDeadlineRequestedInfo &)>
 
using QOSDeadlineOfferedCallbackType = std::function< void(QOSDeadlineOfferedInfo &)>
 
using QOSLivelinessChangedCallbackType = std::function< void(QOSLivelinessChangedInfo &)>
 
using QOSLivelinessLostCallbackType = std::function< void(QOSLivelinessLostInfo &)>
 
using Rate = GenericRate< std::chrono::system_clock >
 
using WallRate = GenericRate< std::chrono::steady_clock >
 
using SubscriptionOptions = SubscriptionOptionsWithAllocator< std::allocator< void > >
 
using VoidCallbackType = std::function< void()>
 
using TimerCallbackType = std::function< void(TimerBase &)>
 

Enumerations

enum  IntraProcessSetting { IntraProcessSetting::Enable, IntraProcessSetting::Disable, IntraProcessSetting::NodeDefault }
 Used as argument in create_publisher and create_subscriber. More...
 
enum  ParameterType : uint8_t {
  PARAMETER_NOT_SET = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET, PARAMETER_BOOL = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, PARAMETER_INTEGER = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, PARAMETER_DOUBLE = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE,
  PARAMETER_STRING = rcl_interfaces::msg::ParameterType::PARAMETER_STRING, PARAMETER_BYTE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, PARAMETER_BOOL_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, PARAMETER_INTEGER_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY,
  PARAMETER_DOUBLE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, PARAMETER_STRING_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY
}
 

Functions

std::vector< Context::SharedPtr > get_contexts ()
 Return a copy of the list of context shared pointers. More...
 
template<typename MessageT , typename AllocatorT = std::allocator<void>, typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
std::shared_ptr< PublisherT > create_publisher (rclcpp::node_interfaces::NodeTopicsInterface *node_topics, const std::string &topic_name, const rmw_qos_profile_t &qos_profile, const PublisherEventCallbacks &event_callbacks, rclcpp::callback_group::CallbackGroup::SharedPtr group, bool use_intra_process_comms, std::shared_ptr< AllocatorT > allocator)
 
template<typename MessageT , typename AllocatorT = std::allocator<void>, typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>, typename NodeT >
std::shared_ptr< PublisherT > create_publisher (NodeT &node, const std::string &topic_name, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
 Create and return a publisher of the given MessageT type. More...
 
template<typename ServiceT , typename CallbackT >
rclcpp::Service< ServiceT >::SharedPtr create_service (std::shared_ptr< node_interfaces::NodeBaseInterface > node_base, std::shared_ptr< node_interfaces::NodeServicesInterface > node_services, const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::callback_group::CallbackGroup::SharedPtr group)
 
template<typename MessageT , typename CallbackT , typename AllocatorT , typename CallbackMessageT , typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>>
std::shared_ptr< SubscriptionT > create_subscription (rclcpp::node_interfaces::NodeTopicsInterface *node_topics, const std::string &topic_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, const SubscriptionEventCallbacks &event_callbacks, rclcpp::callback_group::CallbackGroup::SharedPtr group, bool ignore_local_publications, bool use_intra_process_comms, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< CallbackMessageT, AllocatorT >::SharedPtr msg_mem_strat, typename std::shared_ptr< AllocatorT > allocator)
 
template<typename MessageT , typename CallbackT , typename AllocatorT = std::allocator<void>, typename CallbackMessageT = typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>, typename NodeT >
std::shared_ptr< SubscriptionT > create_subscription (NodeT &&node, const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()), typename rclcpp::message_memory_strategy::MessageMemoryStrategy< CallbackMessageT, AllocatorT >::SharedPtr msg_mem_strat=nullptr)
 Create and return a subscription of the given MessageT type. More...
 
void spin_some (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
 Create a default single-threaded executor and execute any immediately available work. More...
 
void spin_some (rclcpp::Node::SharedPtr node_ptr)
 
void spin (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
 Create a default single-threaded executor and spin the specified node. More...
 
void spin (rclcpp::Node::SharedPtr node_ptr)
 
template<typename FutureT , typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode spin_until_future_complete (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, std::shared_future< FutureT > &future, std::chrono::duration< TimeRepT, TimeT > timeout=std::chrono::duration< TimeRepT, TimeT >(-1))
 
template<typename NodeT = rclcpp::Node, typename FutureT , typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode spin_until_future_complete (std::shared_ptr< NodeT > node_ptr, std::shared_future< FutureT > &future, std::chrono::duration< TimeRepT, TimeT > timeout=std::chrono::duration< TimeRepT, TimeT >(-1))
 
std::string expand_topic_or_service_name (const std::string &name, const std::string &node_name, const std::string &namespace_, bool is_service=false)
 Expand a topic or service name and throw if it is not valid. More...
 
Logger get_logger (const std::string &name)
 Return a named logger. More...
 
Logger get_node_logger (const rcl_node_t *node)
 Return a named logger using an rcl_node_t. More...
 
RCLCPP_LOCAL std::string extend_name_with_sub_namespace (const std::string &name, const std::string &sub_namespace)
 
std::string _to_json_dict_entry (const Parameter &param)
 Return a json encoded version of the parameter intended for a dict. More...
 
std::ostreamoperator<< (std::ostream &os, const rclcpp::Parameter &pv)
 
std::ostreamoperator<< (std::ostream &os, const std::vector< Parameter > &parameters)
 
ParameterMap parameter_map_from (const rcl_params_t *const c_params)
 
ParameterValue parameter_value_from (const rcl_variant_t *const c_value)
 
std::string to_string (ParameterType type)
 Return the name of a parameter type. More...
 
std::ostreamoperator<< (std::ostream &os, ParameterType type)
 
std::string to_string (const ParameterValue &type)
 Return the value of a parameter as a string. More...
 
template<typename MessageT , typename Alloc , typename PublisherT >
PublisherFactory create_publisher_factory (const PublisherEventCallbacks &event_callbacks, std::shared_ptr< Alloc > allocator)
 Return a PublisherFactory with functions setup for creating a PublisherT<MessageT, Alloc>. More...
 
template<typename Callable >
ScopeExit< Callable > make_scope_exit (Callable callable)
 
template<typename MessageT , typename CallbackT , typename Alloc , typename CallbackMessageT , typename SubscriptionT >
SubscriptionFactory create_subscription_factory (CallbackT &&callback, const SubscriptionEventCallbacks &event_callbacks, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< CallbackMessageT, Alloc >::SharedPtr msg_mem_strat, std::shared_ptr< Alloc > allocator)
 Return a SubscriptionFactory with functions for creating a SubscriptionT<MessageT, Alloc>. More...
 
Time operator+ (const rclcpp::Duration &lhs, const rclcpp::Time &rhs)
 
void init (int argc, char const *const argv[], const InitOptions &init_options=InitOptions())
 Initialize communications via the rmw implementation and set up a global signal handler. More...
 
bool install_signal_handlers ()
 Install the global signal handler for rclcpp. More...
 
bool signal_handlers_installed ()
 Return true if the signal handlers are installed, otherwise false. More...
 
bool uninstall_signal_handlers ()
 Uninstall the global signal handler for rclcpp. More...
 
std::vector< std::stringinit_and_remove_ros_arguments (int argc, char const *const argv[], const InitOptions &init_options=InitOptions())
 Initialize communications via the rmw implementation and set up a global signal handler. More...
 
std::vector< std::stringremove_ros_arguments (int argc, char const *const argv[])
 Remove ROS-specific arguments from argument vector. More...
 
bool ok (rclcpp::Context::SharedPtr context=nullptr)
 Check rclcpp's status. More...
 
bool is_initialized (rclcpp::Context::SharedPtr context=nullptr)
 Return true if init() has already been called for the given context. More...
 
bool shutdown (rclcpp::Context::SharedPtr context=nullptr, const std::string &reason="user called rclcpp::shutdown()")
 Shutdown rclcpp context, invalidating it for derived entities. More...
 
void on_shutdown (std::function< void()> callback, rclcpp::Context::SharedPtr context=nullptr)
 Register a function to be called when shutdown is called on the context. More...
 
bool sleep_for (const std::chrono::nanoseconds &nanoseconds, rclcpp::Context::SharedPtr context=nullptr)
 Use the global condition variable to block for the specified amount of time. More...
 
template<typename T >
bool add_will_overflow (const T x, const T y)
 Safely check if addition will overflow. More...
 
template<typename T >
bool add_will_underflow (const T x, const T y)
 Safely check if addition will underflow. More...
 
template<typename T >
bool sub_will_overflow (const T x, const T y)
 Safely check if subtraction will overflow. More...
 
template<typename T >
bool sub_will_underflow (const T x, const T y)
 Safely check if subtraction will underflow. More...
 
const char * get_c_string (const char *string_in)
 Return the given string. More...
 
const char * get_c_string (const std::string &string_in)
 Return the C string from the given std::string. More...
 

Detailed Description

This header provides the get_node_topics_interface() template function.

This function is useful for getting the NodeTopicsInterface pointer from various kinds of Node-like classes.

It's able to get the NodeTopicsInterface pointer so long as the class has a method called get_node_topics_interface() which returns either a pointer (const or not) to a NodeTopicsInterface or a std::shared_ptr to a NodeTopicsInterface.

Typedef Documentation

◆ ParameterMap

A map of fully qualified node names to a list of parameters.

◆ PublisherOptions

◆ QOSDeadlineRequestedInfo

◆ QOSDeadlineOfferedInfo

◆ QOSLivelinessChangedInfo

◆ QOSLivelinessLostInfo

◆ QOSDeadlineRequestedCallbackType

◆ QOSDeadlineOfferedCallbackType

◆ QOSLivelinessChangedCallbackType

◆ QOSLivelinessLostCallbackType

◆ Rate

◆ WallRate

◆ SubscriptionOptions

◆ VoidCallbackType

using rclcpp::VoidCallbackType = typedef std::function<void ()>

◆ TimerCallbackType

Enumeration Type Documentation

◆ IntraProcessSetting

Used as argument in create_publisher and create_subscriber.

Enumerator
Enable 

Explicitly enable intraprocess comm at publisher/subscription level.

Disable 

Explicitly disable intraprocess comm at publisher/subscription level.

NodeDefault 

Take intraprocess configuration from the node.

◆ ParameterType

enum rclcpp::ParameterType : uint8_t
Enumerator
PARAMETER_NOT_SET 
PARAMETER_BOOL 
PARAMETER_INTEGER 
PARAMETER_DOUBLE 
PARAMETER_STRING 
PARAMETER_BYTE_ARRAY 
PARAMETER_BOOL_ARRAY 
PARAMETER_INTEGER_ARRAY 
PARAMETER_DOUBLE_ARRAY 
PARAMETER_STRING_ARRAY 

Function Documentation

◆ get_contexts()

std::vector<Context::SharedPtr> rclcpp::get_contexts ( )

Return a copy of the list of context shared pointers.

This function is thread-safe.

◆ create_publisher() [1/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
std::shared_ptr<PublisherT> rclcpp::create_publisher ( rclcpp::node_interfaces::NodeTopicsInterface node_topics,
const std::string topic_name,
const rmw_qos_profile_t qos_profile,
const PublisherEventCallbacks event_callbacks,
rclcpp::callback_group::CallbackGroup::SharedPtr  group,
bool  use_intra_process_comms,
std::shared_ptr< AllocatorT >  allocator 
)

◆ create_publisher() [2/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>, typename NodeT >
std::shared_ptr<PublisherT> rclcpp::create_publisher ( NodeT &  node,
const std::string topic_name,
const rclcpp::QoS qos,
const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &  options = (    rclcpp::PublisherOptionsWithAllocator<AllocatorT>()) 
)

Create and return a publisher of the given MessageT type.

The NodeT type only needs to have a method called get_node_topics_interface() which returns a shared_ptr to a NodeTopicsInterface.

◆ create_service()

template<typename ServiceT , typename CallbackT >
rclcpp::Service<ServiceT>::SharedPtr rclcpp::create_service ( std::shared_ptr< node_interfaces::NodeBaseInterface node_base,
std::shared_ptr< node_interfaces::NodeServicesInterface node_services,
const std::string service_name,
CallbackT &&  callback,
const rmw_qos_profile_t qos_profile,
rclcpp::callback_group::CallbackGroup::SharedPtr  group 
)

Create a service with a given type.

◆ create_subscription() [1/2]

template<typename MessageT , typename CallbackT , typename AllocatorT , typename CallbackMessageT , typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>>
std::shared_ptr<SubscriptionT> rclcpp::create_subscription ( rclcpp::node_interfaces::NodeTopicsInterface node_topics,
const std::string topic_name,
CallbackT &&  callback,
const rmw_qos_profile_t qos_profile,
const SubscriptionEventCallbacks event_callbacks,
rclcpp::callback_group::CallbackGroup::SharedPtr  group,
bool  ignore_local_publications,
bool  use_intra_process_comms,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy< CallbackMessageT, AllocatorT >::SharedPtr  msg_mem_strat,
typename std::shared_ptr< AllocatorT >  allocator 
)

◆ create_subscription() [2/2]

template<typename MessageT , typename CallbackT , typename AllocatorT = std::allocator<void>, typename CallbackMessageT = typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>, typename NodeT >
std::shared_ptr<SubscriptionT> rclcpp::create_subscription ( NodeT &&  node,
const std::string topic_name,
const rclcpp::QoS qos,
CallbackT &&  callback,
const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &  options = (    rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()  ),
typename rclcpp::message_memory_strategy::MessageMemoryStrategy< CallbackMessageT, AllocatorT >::SharedPtr  msg_mem_strat = nullptr 
)

Create and return a subscription of the given MessageT type.

The NodeT type only needs to have a method called get_node_topics_interface() which returns a shared_ptr to a NodeTopicsInterface, or be a NodeTopicsInterface pointer itself.

◆ spin_some() [1/2]

void rclcpp::spin_some ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_ptr)

Create a default single-threaded executor and execute any immediately available work.

Parameters
[in]node_ptrShared pointer to the node to spin.

◆ spin_some() [2/2]

void rclcpp::spin_some ( rclcpp::Node::SharedPtr  node_ptr)

◆ spin() [1/2]

void rclcpp::spin ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_ptr)

Create a default single-threaded executor and spin the specified node.

Parameters
[in]node_ptrShared pointer to the node to spin.

◆ spin() [2/2]

void rclcpp::spin ( rclcpp::Node::SharedPtr  node_ptr)

◆ spin_until_future_complete() [1/2]

template<typename FutureT , typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode rclcpp::spin_until_future_complete ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_ptr,
std::shared_future< FutureT > &  future,
std::chrono::duration< TimeRepT, TimeT >  timeout = std::chrono::duration<TimeRepT, TimeT>(-1) 
)

◆ spin_until_future_complete() [2/2]

template<typename NodeT = rclcpp::Node, typename FutureT , typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode rclcpp::spin_until_future_complete ( std::shared_ptr< NodeT >  node_ptr,
std::shared_future< FutureT > &  future,
std::chrono::duration< TimeRepT, TimeT >  timeout = std::chrono::duration<TimeRepT, TimeT>(-1) 
)

◆ expand_topic_or_service_name()

std::string rclcpp::expand_topic_or_service_name ( const std::string name,
const std::string node_name,
const std::string namespace_,
bool  is_service = false 
)

Expand a topic or service name and throw if it is not valid.

This function can be used to "just" validate a topic or service name too, since expanding the topic name is required to fully validate a name.

If the name is invalid, then InvalidTopicNameError is thrown or InvalidServiceNameError if is_service is true.

This function can take any form of a topic or service name, i.e. it does not have to be a fully qualified name. The node name and namespace are used to expand it if necessary while validating it.

Expansion is done with rcl_expand_topic_name. The validation is doen with rcl_validate_topic_name and rmw_validate_full_topic_name, so details about failures can be found in the documentation for those functions.

Parameters
namethe topic or service name to be validated
node_namethe name of the node associated with the name
namespace_the namespace of the node associated with the name
is_serviceif true InvalidServiceNameError is thrown instead
Returns
expanded (and validated) topic name
Exceptions
InvalidTopicNameErrorif name is invalid and is_service is false
InvalidServiceNameErrorif name is invalid and is_service is true
std::bad_allocif memory cannot be allocated
RCLErrorif an unexpect error occurs

◆ get_logger()

Logger rclcpp::get_logger ( const std::string name)

Return a named logger.

The returned logger's name will include any naming conventions, such as a name prefix. Currently there are no such naming conventions but they may be introduced in the future.

Parameters
[in]namethe name of the logger
Returns
a logger with the fully-qualified name including naming conventions, or
a dummy logger if logging is disabled.

◆ get_node_logger()

Logger rclcpp::get_node_logger ( const rcl_node_t node)

Return a named logger using an rcl_node_t.

This is a convenience function that does error checking and returns the node logger name, or "rclcpp" if it is unable to get the node name.

Parameters
[in]nodethe rcl node from which to get the logger name
Returns
a logger based on the node name, or "rclcpp" if there's an error

◆ extend_name_with_sub_namespace()

RCLCPP_LOCAL std::string rclcpp::extend_name_with_sub_namespace ( const std::string name,
const std::string sub_namespace 
)
inline

◆ _to_json_dict_entry()

std::string rclcpp::_to_json_dict_entry ( const Parameter param)

Return a json encoded version of the parameter intended for a dict.

◆ operator<<() [1/3]

std::ostream& rclcpp::operator<< ( std::ostream os,
const rclcpp::Parameter pv 
)

◆ operator<<() [2/3]

std::ostream& rclcpp::operator<< ( std::ostream os,
const std::vector< Parameter > &  parameters 
)

◆ parameter_map_from()

ParameterMap rclcpp::parameter_map_from ( const rcl_params_t *const  c_params)

Convert parameters from rcl_yaml_param_parser into C++ class instances.

Parameters
[in]c_paramsC structures containing parameters for multiple nodes.
Returns
a map where the keys are fully qualified node names and values a list of parameters.
Exceptions
InvalidParametersExceptionif the rcl_params_t is inconsistent or invalid.

◆ parameter_value_from()

ParameterValue rclcpp::parameter_value_from ( const rcl_variant_t *const  c_value)

Convert parameter value from rcl_yaml_param_parser into a C++ class instance.

Parameters
[in]c_valueC structure containing a value of a parameter.
Returns
an instance of a parameter value
Exceptions
InvalidParameterValueExceptionif the rcl_variant_t is inconsistent or invalid.

◆ to_string() [1/2]

std::string rclcpp::to_string ( ParameterType  type)

Return the name of a parameter type.

◆ operator<<() [3/3]

std::ostream& rclcpp::operator<< ( std::ostream os,
ParameterType  type 
)

◆ to_string() [2/2]

std::string rclcpp::to_string ( const ParameterValue type)

Return the value of a parameter as a string.

◆ create_publisher_factory()

template<typename MessageT , typename Alloc , typename PublisherT >
PublisherFactory rclcpp::create_publisher_factory ( const PublisherEventCallbacks event_callbacks,
std::shared_ptr< Alloc >  allocator 
)

Return a PublisherFactory with functions setup for creating a PublisherT<MessageT, Alloc>.

◆ make_scope_exit()

template<typename Callable >
ScopeExit<Callable> rclcpp::make_scope_exit ( Callable  callable)

◆ create_subscription_factory()

template<typename MessageT , typename CallbackT , typename Alloc , typename CallbackMessageT , typename SubscriptionT >
SubscriptionFactory rclcpp::create_subscription_factory ( CallbackT &&  callback,
const SubscriptionEventCallbacks event_callbacks,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy< CallbackMessageT, Alloc >::SharedPtr  msg_mem_strat,
std::shared_ptr< Alloc >  allocator 
)

Return a SubscriptionFactory with functions for creating a SubscriptionT<MessageT, Alloc>.

◆ operator+()

Time rclcpp::operator+ ( const rclcpp::Duration lhs,
const rclcpp::Time rhs 
)

◆ init()

void rclcpp::init ( int  argc,
char const *const  argv[],
const InitOptions init_options = InitOptions() 
)

Initialize communications via the rmw implementation and set up a global signal handler.

Initializes the global context which is accessible via the function rclcpp::contexts::default_context::get_global_default_context(). Also, installs the global signal handlers with the function rclcpp::install_signal_handlers().

See also
rclcpp::Context::init() for more details on arguments and possible exceptions

◆ install_signal_handlers()

bool rclcpp::install_signal_handlers ( )

Install the global signal handler for rclcpp.

This function should only need to be run one time per process. It is implicitly run by rclcpp::init(), and therefore this function does not need to be run manually if rclcpp::init() has already been run.

The signal handler will shutdown all initialized context. It will also interrupt any blocking functions in ROS allowing them react to any changes in the state of the system (like shutdown).

This function is thread-safe.

Returns
true if signal handler was installed by this function, false if already installed.

◆ signal_handlers_installed()

bool rclcpp::signal_handlers_installed ( )

Return true if the signal handlers are installed, otherwise false.

◆ uninstall_signal_handlers()

bool rclcpp::uninstall_signal_handlers ( )

Uninstall the global signal handler for rclcpp.

This function does not necessarily need to be called, but can be used to undo what rclcpp::install_signal_handlers() or rclcpp::init() do with respect to signal handling. If you choose to use it, this function only needs to be run one time. It is implicitly run by rclcpp::shutdown(), and therefore this function does not need to be run manually if rclcpp::shutdown() has already been run.

This function is thread-safe.

Returns
true if signal handler was uninstalled by this function, false if was not installed.

◆ init_and_remove_ros_arguments()

std::vector<std::string> rclcpp::init_and_remove_ros_arguments ( int  argc,
char const *const  argv[],
const InitOptions init_options = InitOptions() 
)

Initialize communications via the rmw implementation and set up a global signal handler.

Additionally removes ROS-specific arguments from the argument vector.

See also
rclcpp::Context::init() for more details on arguments and possible exceptions
Returns
Members of the argument vector that are not ROS arguments.
Exceptions
anythingremove_ros_arguments can throw

◆ remove_ros_arguments()

std::vector<std::string> rclcpp::remove_ros_arguments ( int  argc,
char const *const  argv[] 
)

Remove ROS-specific arguments from argument vector.

Some arguments may not have been intended as ROS arguments. This function populates the arguments in a vector. Since the first argument is always assumed to be a process name, the vector will always contain the process name.

Parameters
[in]argcNumber of arguments.
[in]argvArgument vector.
Returns
Members of the argument vector that are not ROS arguments.
Exceptions
anythingthrow_from_rcl_error can throw
rclcpp::exceptions::RCLErrorBaseif the parsing fails

◆ ok()

bool rclcpp::ok ( rclcpp::Context::SharedPtr  context = nullptr)

Check rclcpp's status.

This may return false for a context which has been shutdown, or for a context that was shutdown due to SIGINT being received by the rclcpp signal handler.

If nullptr is given for the context, then the global context is used, i.e. the context initialized by rclcpp::init().

Parameters
[in]contextCheck for shutdown of this Context.
Returns
true if shutdown has been called, false otherwise

◆ is_initialized()

bool rclcpp::is_initialized ( rclcpp::Context::SharedPtr  context = nullptr)

Return true if init() has already been called for the given context.

If nullptr is given for the context, then the global context is used, i.e. the context initialized by rclcpp::init().

Deprecated, as it is no longer different from rcl_ok().

Parameters
[in]contextCheck for initialization of this Context.
Returns
true if the context is initialized, and false otherwise

◆ shutdown()

bool rclcpp::shutdown ( rclcpp::Context::SharedPtr  context = nullptr,
const std::string reason = "user called rclcpp::shutdown()" 
)

Shutdown rclcpp context, invalidating it for derived entities.

If nullptr is given for the context, then the global context is used, i.e. the context initialized by rclcpp::init().

If the global context is used, then the signal handlers are also uninstalled.

This will also cause the "on_shutdown" callbacks to be called.

See also
rclcpp::Context::shutdown()
Parameters
[in]contextto be shutdown
Returns
true if shutdown was successful, false if context was already shutdown

◆ on_shutdown()

void rclcpp::on_shutdown ( std::function< void()>  callback,
rclcpp::Context::SharedPtr  context = nullptr 
)

Register a function to be called when shutdown is called on the context.

If nullptr is given for the context, then the global context is used, i.e. the context initialized by rclcpp::init().

These callbacks are called when the associated Context is shutdown with the Context::shutdown() method. When shutdown by the SIGINT handler, shutdown, and therefore these callbacks, is called asynchronously from the dedicated signal handling thread, at some point after the SIGINT signal is received.

See also
rclcpp::Context::on_shutdown()
Parameters
[in]callbackto be called when the given context is shutdown
[in]contextwith which to associate the context

◆ sleep_for()

bool rclcpp::sleep_for ( const std::chrono::nanoseconds nanoseconds,
rclcpp::Context::SharedPtr  context = nullptr 
)

Use the global condition variable to block for the specified amount of time.

This function can be interrupted early if the associated context becomes invalid due to shutdown() or the signal handler.

See also
rclcpp::Context::sleep_for

If nullptr is given for the context, then the global context is used, i.e. the context initialized by rclcpp::init().

Parameters
[in]nanosecondsA std::chrono::duration representing how long to sleep for.
[in]contextwhich may interrupt this sleep
Returns
true if the condition variable did not timeout.

◆ add_will_overflow()

template<typename T >
bool rclcpp::add_will_overflow ( const T  x,
const T  y 
)

Safely check if addition will overflow.

The type of the operands, T, should have defined std::numeric_limits<T>::max(), >, < and - operators.

Parameters
[in]xis the first addend.
[in]yis the second addend.
Template Parameters
Tis type of the operands.
Returns
True if the x + y sum is greater than T::max value.

◆ add_will_underflow()

template<typename T >
bool rclcpp::add_will_underflow ( const T  x,
const T  y 
)

Safely check if addition will underflow.

The type of the operands, T, should have defined std::numeric_limits<T>::min(), >, < and - operators.

Parameters
[in]xis the first addend.
[in]yis the second addend.
Template Parameters
Tis type of the operands.
Returns
True if the x + y sum is less than T::min value.

◆ sub_will_overflow()

template<typename T >
bool rclcpp::sub_will_overflow ( const T  x,
const T  y 
)

Safely check if subtraction will overflow.

The type of the operands, T, should have defined std::numeric_limits<T>::max(), >, < and + operators.

Parameters
[in]xis the minuend.
[in]yis the subtrahend.
Template Parameters
Tis type of the operands.
Returns
True if the difference x - y sum is grater than T::max value.

◆ sub_will_underflow()

template<typename T >
bool rclcpp::sub_will_underflow ( const T  x,
const T  y 
)

Safely check if subtraction will underflow.

The type of the operands, T, should have defined std::numeric_limits<T>::min(), >, < and + operators.

Parameters
[in]xis the minuend.
[in]yis the subtrahend.
Template Parameters
Tis type of the operands.
Returns
True if the difference x - y sum is less than T::min value.

◆ get_c_string() [1/2]

const char* rclcpp::get_c_string ( const char *  string_in)

Return the given string.

This function is overloaded to transform any string to C-style string.

Parameters
[in]string_inis the string to be returned
Returns
the given string

◆ get_c_string() [2/2]

const char* rclcpp::get_c_string ( const std::string string_in)

Return the C string from the given std::string.

Parameters
[in]string_inis a std::string
Returns
the C string from the std::string