21#include <geometry_msgs/msg/quaternion_stamped.hpp>
27#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
39 RCLCPP_ERROR(
getLogger(),
"[CbNavigateBackwards] distance must be greater or equal than 0");
40 this->backwardDistance = 0;
51 getLogger(),
"[CbNavigateBackwards] Straight backwards motion distance: " << dist);
55 auto currentPoseMsg = p->toPoseMsg();
56 tf2::Transform currentPose;
57 tf2::fromMsg(currentPoseMsg, currentPose);
59 tf2::Transform backwardDeltaTransform;
60 backwardDeltaTransform.setIdentity();
61 backwardDeltaTransform.setOrigin(tf2::Vector3(-dist, 0, 0));
63 tf2::Transform targetPose = currentPose * backwardDeltaTransform;
66 goal.pose.header.frame_id = referenceFrame;
67 goal.pose.header.stamp =
getNode()->now();
68 tf2::toMsg(targetPose, goal.pose.pose);
69 RCLCPP_INFO_STREAM(
getLogger(),
"[CbNavigateBackwards] TARGET POSE BACKWARDS: " << goal.pose);
71 geometry_msgs::msg::PoseStamped currentStampedPoseMsg;
72 currentStampedPoseMsg.header.frame_id = referenceFrame;
73 currentStampedPoseMsg.header.stamp =
getNode()->now();
74 tf2::toMsg(currentPose, currentStampedPoseMsg.pose);
cl_nav2z::ClNav2Z * moveBaseClient_
cl_nav2z::odom_tracker::OdomTracker * odomTracker_
CbNavigateBackwards(float backwardDistance)
void setGoalCheckerId(std::string goal_checker_id)
void setBackwardPlanner()
const std::string & getReferenceFrame() const
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
virtual rclcpp::Logger getLogger()
virtual rclcpp::Node::SharedPtr getNode()
TComponent * getComponent()
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
typename ActionClient::Goal Goal