SMACC2
Loading...
Searching...
No Matches
cb_undo_path_backwards.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
25
26namespace cl_nav2z
27{
28using ::cl_nav2z::odom_tracker::OdomTracker;
29using ::cl_nav2z::odom_tracker::WorkingMode;
30
31using namespace std::chrono_literals;
32
33CbUndoPathBackwards::CbUndoPathBackwards(std::optional<CbUndoPathBackwardsOptions> options)
34{
35 options_ = options;
36}
37
39{
40 listener = std::make_shared<tf2_ros::Buffer>(this->getNode()->get_clock());
42
44
45 auto plannerSwitcher = nav2zClient_->getComponent<PlannerSwitcher>();
46
47 nav_msgs::msg::Path forwardpath = odomTracker->getPath();
48 // RCLCPP_INFO_STREAM(getLogger(),"[UndoPathBackward] Current path backwards: " << forwardpath);
49
50 odomTracker->setWorkingMode(WorkingMode::CLEAR_PATH);
51
52 ClNav2Z::Goal goal;
53
54 auto goalCheckerSwitcher = nav2zClient_->getComponent<GoalCheckerSwitcher>();
55
56 if (options_ && options_->goalCheckerId_)
57 {
58 goalCheckerSwitcher->setGoalCheckerId(*options_->goalCheckerId_);
59 }
60 else
61 {
62 goalCheckerSwitcher->setGoalCheckerId("undo_path_backwards_goal_checker");
63 }
64
65 // WARNING: There might be some race condition with the remote undo global planner were the global path was not
66 // received yet
67 // TODO: waiting notification from global planner that it is loaded
68 rclcpp::sleep_for(1s);
69
70 // this line is used to flush/reset backward planner in the case it were already there
71 // plannerSwitcher->setDefaultPlanners();
72 if (forwardpath.poses.size() > 0)
73 {
74 goal.pose = forwardpath.poses.front();
75 //goal.pose.header.stamp = getNode()->now();
76 goal.pose.header.stamp = rclcpp::Time(0);
77
78 if (options_ && options_->undoControllerName_)
79 {
80 plannerSwitcher->setUndoPathBackwardPlanner(false);
81 RCLCPP_INFO_STREAM(
82 getLogger(),
83 "[" << getName() << "] Undoing path with controller: " << *options_->undoControllerName_);
84 plannerSwitcher->setDesiredController(*options_->undoControllerName_);
85 plannerSwitcher->commitPublish();
86 }
87 else
88 {
89 plannerSwitcher->setUndoPathBackwardPlanner();
90 }
91
92 this->sendGoal(goal);
93 }
94}
95
97{
98 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Exiting: undo navigation ");
99
100 if (this->navigationResult_ == rclcpp_action::ResultCode::SUCCEEDED)
101 {
102 RCLCPP_INFO_STREAM(
103 getLogger(), getName() << " - [CbUndoPathBackwards] Exiting: undo navigation successful, "
104 "popping odom tracker path");
107
109 }
110 else
111 {
112 RCLCPP_INFO_STREAM(
113 getLogger(), getName() << " - [CbUndoPathBackwards] Exiting: undo navigation abort, avoiding "
114 "popping current path");
115
118 // navigation interrupted or aborted. The path may be not totally undone.
119 // We keep the odom tracker in its current state, probably in the middle of the undoing process.
120 // Could you try to repeat the behavior?
121 }
122}
123
124} // namespace cl_nav2z
std::optional< CbUndoPathBackwardsOptions > options_
std::shared_ptr< tf2_ros::Buffer > listener
CbUndoPathBackwards(std::optional< CbUndoPathBackwardsOptions > options=std::nullopt)
void setGoalCheckerId(std::string goal_checker_id)
void logStateString(bool debug=true)
void setWorkingMode(WorkingMode workingMode)
void popPath(int pathCount=1, bool keepPreviousPath=false)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
TComponent * getComponent()