SMACC2
Loading...
Searching...
No Matches
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 <tf2/utils.h>
23#include <cl_nav2z/common.hpp>
27#include <geometry_msgs/msg/quaternion_stamped.hpp>
28#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
29
30namespace cl_nav2z
31{
32using namespace ::cl_nav2z::odom_tracker;
33using namespace smacc2;
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 this->requiresComponent(p, ComponentRequirement::HARD);
55
56 auto referenceFrame = p->getReferenceFrame();
57 auto currentPoseMsg = p->toPoseMsg();
58 tf2::Transform currentPose;
59 tf2::fromMsg(currentPoseMsg, currentPose);
60
61 tf2::Transform backwardDeltaTransform;
62 backwardDeltaTransform.setIdentity();
63 backwardDeltaTransform.setOrigin(tf2::Vector3(-dist, 0, 0));
64
65 tf2::Transform targetPose = currentPose * backwardDeltaTransform;
66
67 nav2_msgs::action::NavigateToPose::Goal goal;
68 goal.pose.header.frame_id = referenceFrame;
69 //goal.pose.header.stamp = getNode()->now();
70 tf2::toMsg(targetPose, goal.pose.pose);
71 RCLCPP_INFO_STREAM(getLogger(), "[CbNavigateBackwards] TARGET POSE BACKWARDS: " << goal.pose);
72
73 geometry_msgs::msg::PoseStamped currentStampedPoseMsg;
74 currentStampedPoseMsg.header.frame_id = referenceFrame;
75 currentStampedPoseMsg.header.stamp = getNode()->now();
76 tf2::toMsg(currentPose, currentStampedPoseMsg.pose);
77
79 requiresComponent(odomTracker_, ComponentRequirement::SOFT);
80
81 if (odomTracker_ != nullptr)
82 {
83 this->odomTracker_->clearPath();
84 this->odomTracker_->setStartPoint(currentStampedPoseMsg);
85 this->odomTracker_->setWorkingMode(WorkingMode::RECORD_PATH);
86 }
87
88 CpPlannerSwitcher * plannerSwitcher;
89 requiresComponent(plannerSwitcher, ComponentRequirement::HARD);
90 plannerSwitcher->setBackwardPlanner();
91
92 CpGoalCheckerSwitcher * goalCheckerSwitcher;
93 requiresComponent(goalCheckerSwitcher, ComponentRequirement::HARD);
94 goalCheckerSwitcher->setGoalCheckerId("backward_goal_checker");
95
96 this->sendGoal(goal);
97}
98
100{
101 if (odomTracker_)
102 {
103 this->odomTracker_->setWorkingMode(WorkingMode::IDLE);
104 }
105}
106
107} // namespace cl_nav2z
void sendGoal(nav2_msgs::action::NavigateToPose::Goal &goal)
cl_nav2z::odom_tracker::CpOdomTracker * odomTracker_
CbNavigateBackwards(float backwardDistanceMeters)
void setGoalCheckerId(std::string goal_checker_id)
void setBackwardPlanner(bool commit=true)
geometry_msgs::msg::Pose toPoseMsg()
Definition cp_pose.hpp:57
const std::string & getReferenceFrame() const
Definition cp_pose.hpp:79
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)