Class BabelFish
Defined in File babel_fish.hpp
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.
-
~BabelFish()
Wrapper for create_subscription without type.
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.
Wrapper for create_subscription using type.
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 = {})
Creates a service server for the given service name and type.
- Parameters:
service_name – The name under which the service should be registered.
type – The type of the service, e.g., rcl_interfaces/srv/GetParameters
callback – The callback that should be called when the service is called.
- Returns:
A pointer to the created service server.
Creates a service server for the given service name and type.
- Parameters:
service_name – The name under which the service should be registered.
type – The type of the service, e.g., rcl_interfaces/srv/GetParameters
callback – The callback that should be called when the service is called.
- Returns:
A pointer to the created service server.
Creates a service client for the given service name and type.
- Parameters:
service_name – The name under which the service server is registered.
type – The type of the service, e.g., rcl_interfaces/srv/GetParameters
- Returns:
A service client that can be used to call the service.
Creates an action server for the given name and type.
- Parameters:
name – The name under which the action server is registered.
type – They type of the action.
handle_goal – Callback when a new goal was received.
handle_cancel – Callback when a cancel request was received.
handle_accepted – Callback when a goal was accepted. Should start executing the goal.
- Returns:
An action server that goals can be sent to for processing.
Creates an action client for the given name and type.
- Parameters:
name – The name under which the action server is registered.
type – The type of the action
- Returns:
An action client that can be used to send goals to the action server.
-
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/msg/Header”
- Throws:
BabelFishException – If the message description was not found
- Returns:
An empty message of the given type
Creates an empty message of the given type.
- Parameters:
type – The message type, e.g.: “std_msgs/msg/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., rcl_interfaces/srv/GetParameters
- 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
Creates a service request message for the given service type.
- Parameters:
type – The type of the service, e.g., rcl_interfaces/srv/GetParameters
- 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 create_action_goal(const std::string &type) const
Creates an empty action goal for the given action type.
- Parameters:
type – The type of the action, e.g., example_interfaces/action/Fibonacci
- Returns:
An empty action goal message that can be used to send a goal to an action server.
-
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()
-
BabelFish()