rclcpp
master
C++ ROS Client Library API
|
Classes | |
class | AnyServiceCallback |
class | AnySubscriptionCallback |
class | AsyncParametersClient |
class | Client |
class | ClientBase |
class | Clock |
class | Context |
class | Duration |
class | Event |
class | GenericRate |
class | GenericTimer |
Generic timer templated on the clock type. Periodically executes a user-specified callback. More... | |
class | JumpHandler |
class | JumpThreshold |
A class to store a threshold for a TimeJump. More... | |
class | Logger |
class | Node |
Node is the single point of entry for creating publishers and subscribers. More... | |
class | ParameterEventsFilter |
class | ParameterService |
class | Publisher |
A publisher publishes messages of any type to a topic. More... | |
class | PublisherBase |
struct | PublisherFactory |
Factory with functions used to create a MessageT specific PublisherT. More... | |
class | RateBase |
struct | ScopeExit |
class | Service |
class | ServiceBase |
class | Subscription |
Subscription implementation, templated on the type of message this subscription receives. More... | |
class | SubscriptionBase |
struct | SubscriptionFactory |
Factory with functions used to create a Subscription<MessageT>. More... | |
class | SyncParametersClient |
class | Time |
struct | TimeJump |
A struct to represent a timejump. More... | |
class | TimerBase |
class | TimeSource |
Typedefs | |
using | Rate = GenericRate< std::chrono::system_clock > |
using | WallRate = GenericRate< std::chrono::steady_clock > |
using | VoidCallbackType = std::function< void()> |
using | TimerCallbackType = std::function< void(TimerBase &)> |
template<typename CallbackType > | |
using | WallTimer = GenericTimer< CallbackType, std::chrono::steady_clock > |
Functions | |
template<typename MessageT , typename AllocatorT , typename PublisherT > | |
std::shared_ptr< PublisherT > | create_publisher (rclcpp::node_interfaces::NodeTopicsInterface *node_topics, const std::string &topic_name, const rmw_qos_profile_t &qos_profile, bool use_intra_process_comms, std::shared_ptr< AllocatorT > allocator) |
template<typename MessageT , typename CallbackT , typename AllocatorT , typename SubscriptionT > | |
rclcpp::Subscription< MessageT, AllocatorT >::SharedPtr | create_subscription (rclcpp::node_interfaces::NodeTopicsInterface *node_topics, const std::string &topic_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::callback_group::CallbackGroup::SharedPtr group, bool ignore_local_publications, bool use_intra_process_comms, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, AllocatorT >::SharedPtr msg_mem_strat, typename std::shared_ptr< AllocatorT > allocator) |
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 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< int64_t, TimeT > timeout=std::chrono::duration< int64_t, TimeT >(-1)) |
template<typename NodeT = rclcpp::Node, typename FutureT , 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< int64_t, TimeT > timeout=std::chrono::duration< int64_t, 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... | |
template<typename MessageT , typename Alloc , typename PublisherT > | |
PublisherFactory | create_publisher_factory (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 SubscriptionT > | |
SubscriptionFactory | create_subscription_factory (CallbackT &&callback, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, 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 *argv[]) |
Initialize communications via the rmw implementation and set up a global signal handler. More... | |
bool | ok () |
Check rclcpp's status. More... | |
void | shutdown () |
Notify the signal handler and rmw that rclcpp is shutting down. More... | |
void | on_shutdown (std::function< void(void)> callback) |
Register a function to be called when shutdown is called. More... | |
rcl_guard_condition_t * | get_sigint_guard_condition (rcl_wait_set_t *wait_set) |
Get a handle to the rmw guard condition that manages the signal handler. More... | |
void | release_sigint_guard_condition (rcl_wait_set_t *wait_set) |
Release the previously allocated guard condition that manages the signal handler. More... | |
bool | sleep_for (const std::chrono::nanoseconds &nanoseconds) |
Use the global condition variable to block for the specified amount of time. More... | |
using rclcpp::Rate = typedef GenericRate<std::chrono::system_clock> |
using rclcpp::WallRate = typedef GenericRate<std::chrono::steady_clock> |
using rclcpp::VoidCallbackType = typedef std::function<void()> |
using rclcpp::TimerCallbackType = typedef std::function<void(TimerBase &)> |
using rclcpp::WallTimer = typedef GenericTimer<CallbackType, std::chrono::steady_clock> |
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, | ||
bool | use_intra_process_comms, | ||
std::shared_ptr< AllocatorT > | allocator | ||
) |
rclcpp::Subscription<MessageT, AllocatorT>::SharedPtr rclcpp::create_subscription | ( | rclcpp::node_interfaces::NodeTopicsInterface * | node_topics, |
const std::string & | topic_name, | ||
CallbackT && | callback, | ||
const rmw_qos_profile_t & | qos_profile, | ||
rclcpp::callback_group::CallbackGroup::SharedPtr | group, | ||
bool | ignore_local_publications, | ||
bool | use_intra_process_comms, | ||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, AllocatorT >::SharedPtr | msg_mem_strat, | ||
typename std::shared_ptr< AllocatorT > | allocator | ||
) |
void rclcpp::spin_some | ( | rclcpp::node_interfaces::NodeBaseInterface::SharedPtr | node_ptr | ) |
Create a default single-threaded executor and execute any immediately available work.
[in] | node_ptr | Shared pointer to the node to spin. |
void rclcpp::spin_some | ( | rclcpp::Node::SharedPtr | node_ptr | ) |
void rclcpp::spin | ( | rclcpp::node_interfaces::NodeBaseInterface::SharedPtr | node_ptr | ) |
Create a default single-threaded executor and spin the specified node.
[in] | node_ptr | Shared pointer to the node to spin. |
void rclcpp::spin | ( | rclcpp::Node::SharedPtr | node_ptr | ) |
rclcpp::executor::FutureReturnCode rclcpp::spin_until_future_complete | ( | rclcpp::node_interfaces::NodeBaseInterface::SharedPtr | node_ptr, |
std::shared_future< FutureT > & | future, | ||
std::chrono::duration< int64_t, TimeT > | timeout = std::chrono::duration<int64_t, TimeT>(-1) |
||
) |
rclcpp::executor::FutureReturnCode rclcpp::spin_until_future_complete | ( | std::shared_ptr< NodeT > | node_ptr, |
std::shared_future< FutureT > & | future, | ||
std::chrono::duration< int64_t, TimeT > | timeout = std::chrono::duration<int64_t, TimeT>(-1) |
||
) |
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.
name | the topic or service name to be validated |
node_name | the name of the node associated with the name |
namespace_ | the namespace of the node associated with the name |
is_service | if true InvalidServiceNameError is thrown instead |
InvalidTopicNameError | if name is invalid and is_service is false |
InvalidServiceNameError | if name is invalid and is_service is true |
std::bad_alloc | if memory cannot be allocated |
RCLError | if an unexpect error occurs |
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.
[in] | name | the name of the logger |
PublisherFactory rclcpp::create_publisher_factory | ( | std::shared_ptr< Alloc > | allocator | ) |
Return a PublisherFactory with functions setup for creating a PublisherT<MessageT, Alloc>.
ScopeExit<Callable> rclcpp::make_scope_exit | ( | Callable | callable | ) |
SubscriptionFactory rclcpp::create_subscription_factory | ( | CallbackT && | callback, |
typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr | msg_mem_strat, | ||
std::shared_ptr< Alloc > | allocator | ||
) |
Return a SubscriptionFactory with functions for creating a SubscriptionT<MessageT, Alloc>.
Time rclcpp::operator+ | ( | const rclcpp::Duration & | lhs, |
const rclcpp::Time & | rhs | ||
) |
void rclcpp::init | ( | int | argc, |
char * | argv[] | ||
) |
Initialize communications via the rmw implementation and set up a global signal handler.
[in] | argc | Number of arguments. |
[in] | argv | Argument vector. Will eventually be used for passing options to rclcpp. |
bool rclcpp::ok | ( | ) |
Check rclcpp's status.
void rclcpp::shutdown | ( | ) |
Notify the signal handler and rmw that rclcpp is shutting down.
void rclcpp::on_shutdown | ( | std::function< void(void)> | callback | ) |
Register a function to be called when shutdown is called.
Calling the callbacks is the last thing shutdown() does.
rcl_guard_condition_t* rclcpp::get_sigint_guard_condition | ( | rcl_wait_set_t * | wait_set | ) |
Get a handle to the rmw guard condition that manages the signal handler.
The first time that this function is called for a given wait set a new guard condition will be created and returned; thereafter the same guard condition will be returned for the same wait set. This mechanism is designed to ensure that the same guard condition is not reused across wait sets (e.g., when using multiple executors in the same process). Will throw an exception if initialization of the guard condition fails.
wait_set | Pointer to the rcl_wait_set_t that will be using the resulting guard condition. |
void rclcpp::release_sigint_guard_condition | ( | rcl_wait_set_t * | wait_set | ) |
Release the previously allocated guard condition that manages the signal handler.
If you previously called get_sigint_guard_condition() for a given wait set to get a sigint guard condition, then you should call release_sigint_guard_condition() when you're done, to free that condition. Will throw an exception if get_sigint_guard_condition() wasn't previously called for the given wait set.
wait_set | Pointer to the rcl_wait_set_t that was using the resulting guard condition. |
bool rclcpp::sleep_for | ( | const std::chrono::nanoseconds & | nanoseconds | ) |
Use the global condition variable to block for the specified amount of time.
[in] | nanoseconds | A std::chrono::duration representing how long to sleep for. |