AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
publish_pose.cpp
1// Copyright 2025 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/pose_stamped.hpp"
17#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
18
19#define INPUT_KEY_POINT_X "x"
20#define INPUT_KEY_POINT_Y "y"
21#define INPUT_KEY_POINT_Z "z"
22#define INPUT_KEY_ORIENTATION_ROLL "roll"
23#define INPUT_KEY_ORIENTATION_PITCH "pitch"
24#define INPUT_KEY_ORIENTATION_YAW "yaw"
25#define INPUT_KEY_USE_DEGREES "use_degrees"
26#define INPUT_KEY_FRAME_ID "frame_id"
27
29{
30
31class PublishPose : public core::RosPublisherNode<geometry_msgs::msg::PoseStamped>
32{
33public:
34 PublishPose(const std::string & instance_name, const Config & config, const Context & context)
35 : RosPublisherNode(instance_name, config, context)
36 {
37 }
38
39 static BT::PortsList providedPorts()
40 {
41 return providedBasicPorts({
42 BT::InputPort<double>(INPUT_KEY_POINT_X, 0.0, "Target x position in meters."),
43 BT::InputPort<double>(INPUT_KEY_POINT_Y, 0.0, "Target y position in meters."),
44 BT::InputPort<double>(INPUT_KEY_POINT_Z, 0.0, "Target z position in meters."),
45 BT::InputPort<double>(
46 INPUT_KEY_ORIENTATION_ROLL, 0.0, "Target roll angle in radians (or degrees if use_degrees is true)."),
47 BT::InputPort<double>(
48 INPUT_KEY_ORIENTATION_PITCH, 0.0, "Target pitch angle in radians (or degrees if use_degrees is true)."),
49 BT::InputPort<double>(
50 INPUT_KEY_ORIENTATION_YAW, 0.0, "Target yaw angle in radians (or degrees if use_degrees is true)."),
51 BT::InputPort<bool>(
52 INPUT_KEY_USE_DEGREES, false, "If true, interpret roll, pitch, yaw as degrees instead of radians."),
53 BT::InputPort<std::string>(INPUT_KEY_FRAME_ID, "map", "Frame ID for the pose."),
54 });
55 }
56
57 bool setMessage(geometry_msgs::msg::PoseStamped & msg) override final
58 {
59 // Get position inputs
60 const BT::Expected<double> expected_x = getInput<double>(INPUT_KEY_POINT_X);
61 const BT::Expected<double> expected_y = getInput<double>(INPUT_KEY_POINT_Y);
62 const BT::Expected<double> expected_z = getInput<double>(INPUT_KEY_POINT_Z);
63 const BT::Expected<double> expected_roll = getInput<double>(INPUT_KEY_ORIENTATION_ROLL);
64 const BT::Expected<double> expected_pitch = getInput<double>(INPUT_KEY_ORIENTATION_PITCH);
65 const BT::Expected<double> expected_yaw = getInput<double>(INPUT_KEY_ORIENTATION_YAW);
66 const BT::Expected<bool> expected_use_degrees = getInput<bool>(INPUT_KEY_USE_DEGREES);
67 const BT::Expected<std::string> expected_frame_id = getInput<std::string>(INPUT_KEY_FRAME_ID);
68
69 if (
70 !expected_x || !expected_y || !expected_z || !expected_roll || !expected_pitch || !expected_yaw ||
71 !expected_use_degrees || !expected_frame_id) {
72 RCLCPP_ERROR(logger_, "%s - Failed to get input values", context_.getFullyQualifiedTreeNodeName(this).c_str());
73 return false;
74 }
75
76 msg.pose.position.x = expected_x.value();
77 msg.pose.position.y = expected_y.value();
78 msg.pose.position.z = expected_z.value();
79
80 // Convert roll, pitch, yaw to quaternion using tf2
81 double roll = expected_roll.value();
82 double pitch = expected_pitch.value();
83 double yaw = expected_yaw.value();
84
85 // Convert degrees to radians if needed
86 if (expected_use_degrees.value()) {
87 constexpr double DEG_TO_RAD = M_PI / 180.0;
88 roll *= DEG_TO_RAD;
89 pitch *= DEG_TO_RAD;
90 yaw *= DEG_TO_RAD;
91 }
92
93 tf2::Quaternion q;
94 q.setRPY(roll, pitch, yaw);
95 msg.pose.orientation = tf2::toMsg(q);
96
97 // Set frame ID and timestamp
98 msg.header.frame_id = expected_frame_id.value();
99 msg.header.stamp = context_.getCurrentTime();
100
101 RCLCPP_DEBUG(
102 logger_, "%s - Publishing pose: [%.2f, %.2f, %.2f m] [roll=%.2f, pitch=%.2f, yaw=%.2f rad] in frame '%s'",
103 context_.getFullyQualifiedTreeNodeName(this).c_str(), msg.pose.position.x, msg.pose.position.y,
104 msg.pose.position.z, roll, pitch, yaw, msg.header.frame_id.c_str());
105
106 return true;
107 }
108};
109
110} // namespace auto_apms_behavior_tree
111
112AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::PublishPose)
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:44
Powerful tooling for incorporating behavior trees for task development.
Definition behavior.hpp:32