28using ::cl_nav2z::odom_tracker::OdomTracker;
29using ::cl_nav2z::odom_tracker::WorkingMode;
31using namespace std::chrono_literals;
40 listener = std::make_shared<tf2_ros::Buffer>(this->
getNode()->get_clock());
62 goalCheckerSwitcher->setGoalCheckerId(
"undo_path_backwards_goal_checker");
68 rclcpp::sleep_for(1s);
72 if (forwardpath.poses.size() > 0)
74 goal.pose = forwardpath.poses.front();
76 goal.pose.header.stamp = rclcpp::Time(0);
80 plannerSwitcher->setUndoPathBackwardPlanner(
false);
83 "[" <<
getName() <<
"] Undoing path with controller: " << *
options_->undoControllerName_);
84 plannerSwitcher->setDesiredController(*
options_->undoControllerName_);
85 plannerSwitcher->commitPublish();
89 plannerSwitcher->setUndoPathBackwardPlanner();
98 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] Exiting: undo navigation ");
103 getLogger(),
getName() <<
" - [CbUndoPathBackwards] Exiting: undo navigation successful, "
104 "popping odom tracker path");
113 getLogger(),
getName() <<
" - [CbUndoPathBackwards] Exiting: undo navigation abort, avoiding "
114 "popping current path");
void sendGoal(ClNav2Z::Goal &goal)
cl_nav2z::ClNav2Z * nav2zClient_
rclcpp_action::ResultCode navigationResult_
std::optional< CbUndoPathBackwardsOptions > options_
std::shared_ptr< tf2_ros::Buffer > listener
CbUndoPathBackwards(std::optional< CbUndoPathBackwardsOptions > options=std::nullopt)
OdomTracker * odomTracker
void setGoalCheckerId(std::string goal_checker_id)
nav_msgs::msg::Path getPath()
void logStateString(bool debug=true)
void setWorkingMode(WorkingMode workingMode)
void popPath(int pathCount=1, bool keepPreviousPath=false)
std::string getName() const
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
TComponent * getComponent()
typename ActionClient::Goal Goal