35 float x,
float y,
float yaw, std::optional<CbNavigateGlobalPositionOptions> options)
37 auto p = geometry_msgs::msg::Point();
49 goalYaw = tf2::getYaw(pose.orientation);
54 RCLCPP_INFO(
getLogger(),
"Entering Navigate Global position");
55 RCLCPP_INFO(
getLogger(),
"Component requirements completed");
62 plannerSwitcher->setDefaultPlanners(
false);
69 plannerSwitcher->commitPublish();
75 odomTracker->pushPath(pathname);
76 odomTracker->setStartPoint(pose);
77 odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);
89 RCLCPP_INFO(
getLogger(),
"Sending Goal to MoveBase");
91 goal.pose.header.frame_id = referenceFrame;
97 goal.pose.pose.orientation = tf2::toMsg(q);
106 RCLCPP_INFO(
getLogger(),
"Exiting move goal Action Client");
void sendGoal(ClNav2Z::Goal &goal)
cl_nav2z::ClNav2Z * nav2zClient_
void setGoal(const geometry_msgs::msg::Pose &pose)
geometry_msgs::msg::Point goalPosition
virtual void onEntry() override
CbNavigateGlobalPosition()
CbNavigateGlobalPositionOptions options
void setGoalCheckerId(std::string goal_checker_id)
const std::string & getReferenceFrame() const
ISmaccState * getCurrentState()
std::string getName() const
virtual rclcpp::Logger getLogger() const
TComponent * getComponent()
virtual std::string getName()=0
typename ActionClient::Goal Goal
std::optional< std::string > controllerName_