15#ifndef ROBOLIGO_COMMON_CONNECTOR_COMMANDERS__OUTPUT_HPP_
16#define ROBOLIGO_COMMON_CONNECTOR_COMMANDERS__OUTPUT_HPP_
18#include <geometry_msgs/msg/twist.hpp>
19#include <geometry_msgs/msg/twist_stamped.hpp>
20#include <mavros_msgs/msg/position_target.hpp>
34 rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr
publisher;
35 geometry_msgs::msg::Twist::SharedPtr
data;
46 rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr
publisher;
47 geometry_msgs::msg::TwistStamped::SharedPtr
data;
60 rclcpp::Publisher<mavros_msgs::msg::PositionTarget>::SharedPtr
publisher;
61 mavros_msgs::msg::PositionTarget::SharedPtr
data;
81 Output(std::string new_name, std::string new_topic);
98 void set_data(
const geometry_msgs::msg::Twist* msg);
Commander(std::string new_name, std::string new_value)
Constructor for Commander.
Definition Commander.cpp:19
virtual ~Output()=default
Virtual destructor for proper cleanup of derived classes.
RoboligoOutputPositionTarget position_target
Stores target position output data.
Definition Output.hpp:92
RoboligoOutputTwist twist
Stores unstamped twist (velocity) output data.
Definition Output.hpp:88
void set_data(const geometry_msgs::msg::Twist *msg)
Sets output data from an unstamped Twist message.
Definition Output.cpp:27
RoboligoOutputTwistStamped twist_stamped
Stores timestamped twist (velocity) output data.
Definition Output.hpp:90
Output(std::string new_name, std::string new_topic)
Constructs an Output commander with a name and topic.
Definition Output.cpp:19
void set_data_stamped(const geometry_msgs::msg::TwistStamped *msg)
Sets output data from a timestamped TwistStamped message.
Definition Output.cpp:33
Definition ClassificationBase.hpp:28
Encapsulates a ROS 2 publisher and message data for position target commands with control parameters.
Definition Output.hpp:59
mavros_msgs::msg::PositionTarget::SharedPtr data
Definition Output.hpp:61
int type_mask
Definition Output.hpp:63
rclcpp::Publisher< mavros_msgs::msg::PositionTarget >::SharedPtr publisher
Definition Output.hpp:60
int coordinate_frame
Definition Output.hpp:62
Encapsulates a ROS 2 publisher and message data for stamped Twist commands.
Definition Output.hpp:45
rclcpp::Publisher< geometry_msgs::msg::TwistStamped >::SharedPtr publisher
Definition Output.hpp:46
geometry_msgs::msg::TwistStamped::SharedPtr data
Definition Output.hpp:47
Encapsulates a ROS 2 publisher and message data for Twist commands.
Definition Output.hpp:33
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr publisher
Definition Output.hpp:34
geometry_msgs::msg::Twist::SharedPtr data
Definition Output.hpp:35