Class BabelFish

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< BabelFish >

Class Documentation

class BabelFish : public std::enable_shared_from_this<BabelFish>

Allows communication using message types that are not known at compile time.

Public Functions

BabelFish()

Constructs an instance of BabelFish with a new instance of the default description provider. If you have to use multiple BabelFish instances, it is recommended to share the TypeSupportProvider to prevent multiple look ups of the same message.

explicit BabelFish(std::vector<TypeSupportProvider::SharedPtr> type_support_providers)
~BabelFish()
template<typename CallbackT>
inline BabelFishSubscription::SharedPtr create_subscription(rclcpp::Node &node, const std::string &topic, const rclcpp::QoS &qos, CallbackT &&callback, rclcpp::CallbackGroup::SharedPtr group = nullptr, rclcpp::SubscriptionOptions options = {}, std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Wrapper for create_subscription without type.

BabelFishSubscription::SharedPtr create_subscription(rclcpp::Node &node, const std::string &topic, const rclcpp::QoS &qos, rclcpp::AnySubscriptionCallback<CompoundMessage, std::allocator<void>> callback, rclcpp::CallbackGroup::SharedPtr group = nullptr, rclcpp::SubscriptionOptions options = {}, std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

This method will wait for the given topic until timeout expired (if a timeout is set) or the topic becomes available. As soon as the topic is available, it will create a subscription for the topic with the passed options.

Parameters:
  • qos – The quality of service options. Can be a number which will be the queue size, i.e., number of messages to queue for processing before dropping messages if the processing can’t keep up.

  • timeout – The maximum time this call will block before returning. Set to 0 to not block at all.

Throws:

BabelFishException – If the message type for the given topic could not be loaded or a subscription could not be created for any other reason.

Returns:

A subscription if the topic became available before the timeout expired or a nullptr otherwise.

template<typename CallbackT>
inline BabelFishSubscription::SharedPtr create_subscription(rclcpp::Node &node, const std::string &topic, const std::string &type, const rclcpp::QoS &qos, CallbackT &&callback, rclcpp::CallbackGroup::SharedPtr group = nullptr, rclcpp::SubscriptionOptions options = {})

Wrapper for create_subscription using type.

BabelFishSubscription::SharedPtr create_subscription(rclcpp::Node &node, const std::string &topic, const std::string &type, const rclcpp::QoS &qos, rclcpp::AnySubscriptionCallback<CompoundMessage, std::allocator<void>> callback, rclcpp::CallbackGroup::SharedPtr group = nullptr, rclcpp::SubscriptionOptions options = {})

This method will create a subscription for the given topic using the given message type. Since the message type is provided, it will not wait for the topic to become available.

Parameters:
  • type – The message type name for the given topic. E.g.: geometry_msgs/msg/Pose

  • qos – The quality of service options. Can be a number which will be the queue size, i.e., number of messages to queue for processing before dropping messages if the processing can’t keep up.´

Throws:

BabelFishException – If the given message type could not be loaded or a subscription could not be created for any other reason.

Returns:

A subscription to the given topic with the given message type.

BabelFishPublisher::SharedPtr create_publisher(rclcpp::Node &node, const std::string &topic, const std::string &type, const rclcpp::QoS &qos, rclcpp::PublisherOptions options = {})
template<typename CallbackT>
inline BabelFishService::SharedPtr create_service(rclcpp::Node &node, const std::string &service_name, const std::string &type, CallbackT &&callback, const rmw_qos_profile_t &qos_profile = rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group = nullptr)
BabelFishService::SharedPtr create_service(rclcpp::Node &node, const std::string &service_name, const std::string &type, AnyServiceCallback callback, const rmw_qos_profile_t &qos_profile = rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group = nullptr)
BabelFishServiceClient::SharedPtr create_service_client(rclcpp::Node &node, const std::string &service_name, const std::string &type, const rmw_qos_profile_t &qos_profile = rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group = nullptr)
BabelFishActionClient::SharedPtr create_action_client(rclcpp::Node &node, const std::string &name, const std::string &type, const rcl_action_client_options_t &options = rcl_action_client_get_default_options(), rclcpp::CallbackGroup::SharedPtr group = nullptr)
CompoundMessage create_message(const std::string &type) const

Creates an empty message of the given type.

Parameters:

type – The message type, e.g.: “std_msgs/Header”

Throws:

BabelFishException – If the message description was not found

Returns:

An empty message of the given type

CompoundMessage::SharedPtr create_message_shared(const std::string &type) const

Creates an empty message of the given type.

Parameters:

type – The message type, e.g.: “std_msgs/Header”

Throws:

BabelFishException – If the message description was not found

Returns:

An empty message of the given type

CompoundMessage create_service_request(const std::string &type) const

Creates a service request message for the given service type.

Parameters:

type – The type of the service, e.g., rosapi/GetParam

Throws:

BabelFishException – If the service description was not found

Returns:

An empty service request message that can be used to call a service of the given type

CompoundMessage::SharedPtr create_service_request_shared(const std::string &type) const

Creates a service request message for the given service type.

Parameters:

type – The type of the service, e.g., rosapi/GetParam

Throws:

BabelFishException – If the service description was not found

Returns:

An empty service request message that can be used to call a service of the given type

MessageTypeSupport::ConstSharedPtr get_message_type_support(const std::string &type) const
ServiceTypeSupport::ConstSharedPtr get_service_type_support(const std::string &type) const
ActionTypeSupport::ConstSharedPtr get_action_type_support(const std::string &type) const
std::vector<TypeSupportProvider::SharedPtr> type_support_providers()