Added dwm rotate

This commit is contained in:
2025-02-26 16:29:20 +01:00
parent 5e2cc0b5af
commit 43da8a3a37
4 changed files with 82 additions and 5 deletions

View File

@ -8,6 +8,7 @@
#include "mg_msgs/action/move_point.hpp"
#include "mg_msgs/action/move_straight.hpp"
#include "mg_msgs/action/look_at.hpp"
#include "mg_msgs/action/rotate.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
@ -26,12 +27,14 @@ namespace mg {
using MovePoint = mg_msgs::action::MovePoint;
using MoveStraight = mg_msgs::action::MoveStraight;
using LookAt = mg_msgs::action::LookAt;
using Rotate = mg_msgs::action::Rotate;
rclcpp::Publisher<Geometry::TwistStamped>::SharedPtr pub_twist;
rclcpp_action::Server<LookAt>::SharedPtr sv_look_at;
rclcpp_action::Server<MovePoint>::SharedPtr sv_move_point;
rclcpp_action::Server<MoveStraight>::SharedPtr sv_move_straight;
rclcpp_action::Server<LookAt>::SharedPtr sv_look_at;
rclcpp_action::Server<Rotate>::SharedPtr sv_rotate;
rclcpp::Subscription<Geometry::TransformStamped>::SharedPtr tf2_subscription_;
tf2_ros::Buffer::SharedPtr tf2_buffer;