1#include "modulo_core/communication/MessagePair.hpp"
9 : MessagePairInterface(
MessageType::BOOL), data_(std::move(data)), clock_(std::move(clock)) {}
12MessagePair<std_msgs::msg::Float64, double>::MessagePair(
13 std::shared_ptr<double> data, std::shared_ptr<rclcpp::Clock> clock)
14 : MessagePairInterface(
MessageType::FLOAT64), data_(std::move(data)), clock_(std::move(clock)) {}
17MessagePair<std_msgs::msg::Float64MultiArray, std::vector<double>>::MessagePair(
18 std::shared_ptr<std::vector<double>> data, std::shared_ptr<rclcpp::Clock> clock)
19 : MessagePairInterface(
MessageType::FLOAT64_MULTI_ARRAY), data_(std::move(data)), clock_(std::move(clock)) {}
22MessagePair<std_msgs::msg::Int32, int>::MessagePair(std::shared_ptr<int> data, std::shared_ptr<rclcpp::Clock> clock)
23 : MessagePairInterface(
MessageType::INT32), data_(std::move(data)), clock_(std::move(clock)) {}
26MessagePair<std_msgs::msg::String, std::string>::MessagePair(
27 std::shared_ptr<std::string> data, std::shared_ptr<rclcpp::Clock> clock)
28 : MessagePairInterface(
MessageType::STRING), data_(std::move(data)), clock_(std::move(clock)) {}
31MessagePair<EncodedState, state_representation::State>::MessagePair(
32 std::shared_ptr<state_representation::State> data, std::shared_ptr<rclcpp::Clock> clock)
33 : MessagePairInterface(
MessageType::ENCODED_STATE), data_(std::move(data)), clock_(std::move(clock)) {}
MessagePair(std::shared_ptr< DataT > data, std::shared_ptr< rclcpp::Clock > clock)
Constructor of the MessagePair.
Modulo Core communication module for handling messages on publication and subscription interfaces.
MessageType
Enum of all supported ROS message types for the MessagePairInterface.