SMACC2
cb_navigate_backward.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
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/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <geometry_msgs/msg/quaternion_stamped.hpp>
27#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
28
29#include <tf2/utils.h>
30
31namespace cl_nav2z
32{
33using namespace ::cl_nav2z::odom_tracker;
34
36{
37 if (backwardDistance < 0)
38 {
39 RCLCPP_ERROR(getLogger(), "[CbNavigateBackwards] distance must be greater or equal than 0");
40 this->backwardDistance = 0;
41 }
42 this->backwardDistance = backwardDistance;
43}
44
46{
47 // straight motion distance
48 double dist = backwardDistance;
49
50 RCLCPP_INFO_STREAM(
51 getLogger(), "[CbNavigateBackwards] Straight backwards motion distance: " << dist);
52
54 auto referenceFrame = p->getReferenceFrame();
55 auto currentPoseMsg = p->toPoseMsg();
56 tf2::Transform currentPose;
57 tf2::fromMsg(currentPoseMsg, currentPose);
58
59 tf2::Transform backwardDeltaTransform;
60 backwardDeltaTransform.setIdentity();
61 backwardDeltaTransform.setOrigin(tf2::Vector3(-dist, 0, 0));
62
63 tf2::Transform targetPose = currentPose * backwardDeltaTransform;
64
65 ClNav2Z::Goal goal;
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);
70
71 geometry_msgs::msg::PoseStamped currentStampedPoseMsg;
72 currentStampedPoseMsg.header.frame_id = referenceFrame;
73 currentStampedPoseMsg.header.stamp = getNode()->now();
74 tf2::toMsg(currentPose, currentStampedPoseMsg.pose);
75
77 if (odomTracker_ != nullptr)
78 {
79 this->odomTracker_->clearPath();
80 this->odomTracker_->setStartPoint(currentStampedPoseMsg);
81 this->odomTracker_->setWorkingMode(WorkingMode::RECORD_PATH);
82 }
83
84 auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();
85 plannerSwitcher->setBackwardPlanner();
86
87 auto goalCheckerSwitcher = moveBaseClient_->getComponent<GoalCheckerSwitcher>();
88 goalCheckerSwitcher->setGoalCheckerId("backward_goal_checker");
89
91}
92
94{
95 if (odomTracker_)
96 {
97 this->odomTracker_->setWorkingMode(WorkingMode::IDLE);
98 }
99}
100
101} // namespace cl_nav2z
cl_nav2z::odom_tracker::OdomTracker * odomTracker_
CbNavigateBackwards(float backwardDistance)
void setGoalCheckerId(std::string goal_checker_id)
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:77
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
virtual rclcpp::Node::SharedPtr getNode()
TComponent * getComponent()
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)