28using ::cl_nav2z::odom_tracker::CpOdomTracker;
29using ::cl_nav2z::odom_tracker::WorkingMode;
31using namespace std::chrono_literals;
40 listener = std::make_shared<tf2_ros::Buffer>(this->
getNode()->get_clock());
58 if (forwardpath.poses.size() > 0)
60 goal.pose = forwardpath.poses.front();
62 goal.pose.header.stamp = rclcpp::Time(0);
66 plannerSwitcher->setUndoPathBackwardPlanner(
false);
69 "[" <<
getName() <<
"] Undoing path with controller: " << *
options_->undoControllerName_);
70 plannerSwitcher->setDesiredController(*
options_->undoControllerName_);
71 plannerSwitcher->commitPublish();
75 plannerSwitcher->setUndoPathBackwardPlanner();
84 <<
"] Waiting for 5 seconds to get planer/controller and wait goal checker "
88 RCLCPP_ERROR_STREAM(
getLogger(),
"[" <<
getName() <<
"] activating undo navigation planner");
92 goalCheckerSwitcher->setGoalCheckerId(*
options_->goalCheckerId_);
96 goalCheckerSwitcher->setGoalCheckerId(
"undo_path_backwards_goal_checker");
105 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] Exiting: undo navigation ");
110 getLogger(),
getName() <<
" - [CbUndoPathBackwards] Exiting: undo navigation successful, "
111 "popping odom tracker path");
120 getLogger(),
getName() <<
" - [CbUndoPathBackwards] Exiting: undo navigation abort, avoiding "
121 "popping current path");
void sendGoal(ClNav2Z::Goal &goal)
cl_nav2z::ClNav2Z * nav2zClient_
rclcpp_action::ResultCode navigationResult_
std::optional< CbUndoPathBackwardsOptions > options_
CpOdomTracker * odomTracker
std::shared_ptr< tf2_ros::Buffer > listener
CbUndoPathBackwards(std::optional< CbUndoPathBackwardsOptions > options=std::nullopt)
void popPath(int pathCount=1, bool keepPreviousPath=false)
nav_msgs::msg::Path getPath()
void setWorkingMode(WorkingMode workingMode)
void logStateString(bool debug=true)
std::string getName() const
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
TComponent * getComponent()
typename ActionClient::Goal Goal