roboligo
Loading...
Searching...
No Matches
Output.hpp
Go to the documentation of this file.
1// Copyright 2026 Juan S. Cely G.
2
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6
7// https://www.apache.org/licenses/LICENSE-2.0
8
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef ROBOLIGO_COMMON_CONNECTOR_COMMANDERS__OUTPUT_HPP_
16#define ROBOLIGO_COMMON_CONNECTOR_COMMANDERS__OUTPUT_HPP_
17
18#include <geometry_msgs/msg/twist.hpp>
19#include <geometry_msgs/msg/twist_stamped.hpp>
20#include <mavros_msgs/msg/position_target.hpp>
21
23
24namespace roboligo
25{
34 rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher;
35 geometry_msgs::msg::Twist::SharedPtr data;
36 };
37
46 rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr publisher;
47 geometry_msgs::msg::TwistStamped::SharedPtr data;
48 };
49
60 rclcpp::Publisher<mavros_msgs::msg::PositionTarget>::SharedPtr publisher;
61 mavros_msgs::msg::PositionTarget::SharedPtr data;
63 int type_mask = 1991; //b011111000111
64 };
65
73 class Output : public Commander
74 {
75 public:
81 Output(std::string new_name, std::string new_topic);
82
86 virtual ~Output() = default;
87
89
91
93
98 void set_data(const geometry_msgs::msg::Twist* msg);
99
104 void set_data_stamped(const geometry_msgs::msg::TwistStamped* msg);
105 };
106} // namespace roboligo
107#endif // ROBOLIGO_COMMON_CONNECTOR_COMMANDERS__OUTPUT_HPP_
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