AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
publish_twist.cpp
1// Copyright 2026 Robin Müller
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// http://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#include "auto_apms_behavior_tree_core/node.hpp"
16#include "geometry_msgs/msg/twist_stamped.hpp"
17
18#define INPUT_KEY_LINEAR_X "linear_x"
19#define INPUT_KEY_LINEAR_Y "linear_y"
20#define INPUT_KEY_LINEAR_Z "linear_z"
21#define INPUT_KEY_ANGULAR_X "angular_x"
22#define INPUT_KEY_ANGULAR_Y "angular_y"
23#define INPUT_KEY_ANGULAR_Z "angular_z"
24#define INPUT_KEY_FRAME_ID "frame_id"
25
27{
28
29class PublishTwist : public core::RosPublisherNode<geometry_msgs::msg::TwistStamped>
30{
31public:
32 PublishTwist(const std::string & instance_name, const Config & config, const Context & context)
33 : RosPublisherNode(instance_name, config, context)
34 {
35 }
36
37 static BT::PortsList providedPorts()
38 {
39 return providedBasicPorts({
40 BT::InputPort<double>(INPUT_KEY_LINEAR_X, 0.0, "Linear velocity along x-axis in m/s."),
41 BT::InputPort<double>(INPUT_KEY_LINEAR_Y, 0.0, "Linear velocity along y-axis in m/s."),
42 BT::InputPort<double>(INPUT_KEY_LINEAR_Z, 0.0, "Linear velocity along z-axis in m/s."),
43 BT::InputPort<double>(INPUT_KEY_ANGULAR_X, 0.0, "Angular velocity around x-axis in rad/s."),
44 BT::InputPort<double>(INPUT_KEY_ANGULAR_Y, 0.0, "Angular velocity around y-axis in rad/s."),
45 BT::InputPort<double>(INPUT_KEY_ANGULAR_Z, 0.0, "Angular velocity around z-axis in rad/s."),
46 BT::InputPort<std::string>(INPUT_KEY_FRAME_ID, "map", "Frame ID for the twist."),
47 });
48 }
49
50 bool setMessage(geometry_msgs::msg::TwistStamped & msg) override final
51 {
52 const BT::Expected<double> expected_linear_x = getInput<double>(INPUT_KEY_LINEAR_X);
53 const BT::Expected<double> expected_linear_y = getInput<double>(INPUT_KEY_LINEAR_Y);
54 const BT::Expected<double> expected_linear_z = getInput<double>(INPUT_KEY_LINEAR_Z);
55 const BT::Expected<double> expected_angular_x = getInput<double>(INPUT_KEY_ANGULAR_X);
56 const BT::Expected<double> expected_angular_y = getInput<double>(INPUT_KEY_ANGULAR_Y);
57 const BT::Expected<double> expected_angular_z = getInput<double>(INPUT_KEY_ANGULAR_Z);
58 const BT::Expected<std::string> expected_frame_id = getInput<std::string>(INPUT_KEY_FRAME_ID);
59
60 if (
61 !expected_linear_x || !expected_linear_y || !expected_linear_z || !expected_angular_x || !expected_angular_y ||
62 !expected_angular_z || !expected_frame_id) {
63 RCLCPP_ERROR(logger_, "%s - Failed to get input values", context_.getFullyQualifiedTreeNodeName(this).c_str());
64 return false;
65 }
66
67 msg.twist.linear.x = expected_linear_x.value();
68 msg.twist.linear.y = expected_linear_y.value();
69 msg.twist.linear.z = expected_linear_z.value();
70 msg.twist.angular.x = expected_angular_x.value();
71 msg.twist.angular.y = expected_angular_y.value();
72 msg.twist.angular.z = expected_angular_z.value();
73
74 msg.header.frame_id = expected_frame_id.value();
75 msg.header.stamp = context_.getCurrentTime();
76
77 RCLCPP_DEBUG(
78 logger_, "%s - Publishing twist: linear=[%.2f, %.2f, %.2f m/s] angular=[%.2f, %.2f, %.2f rad/s]",
79 context_.getFullyQualifiedTreeNodeName(this).c_str(), msg.twist.linear.x, msg.twist.linear.y, msg.twist.linear.z,
80 msg.twist.angular.x, msg.twist.angular.y, msg.twist.angular.z);
81
82 return true;
83 }
84};
85
86} // namespace auto_apms_behavior_tree
87
88AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::PublishTwist)
Generic behavior tree node wrapper for a ROS 2 publisher.
RosPublisherNode(const std::string &instance_name, const Config &config, Context context, const rclcpp::QoS &qos={10})
#define AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(type)
Macro for registering a behavior tree node plugin.
Definition node.hpp:46
Powerful tooling for incorporating behavior trees for task development.
Definition behavior.hpp:32