36 float x,
float y,
float yaw, std::optional<CbNavigateGlobalPositionOptions> options)
38 auto p = geometry_msgs::msg::Point();
50 goalYaw = tf2::getYaw(pose.orientation);
55 RCLCPP_INFO(
getLogger(),
"Entering Navigate Global position");
56 RCLCPP_INFO(
getLogger(),
"Component requirements completed");
98 RCLCPP_INFO(
getLogger(),
"Sending Goal to MoveBase");
99 nav2_msgs::action::NavigateToPose::Goal goal;
100 goal.pose.header.frame_id = referenceFrame;
106 goal.pose.pose.orientation = tf2::toMsg(q);
115 RCLCPP_INFO(
getLogger(),
"Exiting move goal Action Client");
void sendGoal(nav2_msgs::action::NavigateToPose::Goal &goal)
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)
void setDefaultPlanners(bool commit=true)
void setDesiredController(std::string)
geometry_msgs::msg::Pose toPoseMsg()
const std::string & getReferenceFrame() const
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
ISmaccState * getCurrentState()
std::string getName() const
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
virtual std::string getName()=0
std::optional< std::string > controllerName_