16 auto p = geometry_msgs::Point();
26 goalYaw = tf::getYaw(pose.orientation);
31 ROS_INFO(
"[CbNavigateGlobalPosition] Entering Navigate Global position");
39 odomTracker->pushPath(
"FreeNavigationToGoalPose");
40 odomTracker->setStartPoint(pose);
41 odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);
51 auto currentPoseMsg = p->toPoseMsg();
53 ROS_INFO(
"Sending Goal to MoveBase");
54 ClMoveBaseZ::Goal goal;
55 goal.target_pose.header.frame_id = referenceFrame;
56 goal.target_pose.header.stamp = ros::Time::now();
75 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
80 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(*
goalYaw);
83 ROS_INFO_STREAM(
"start position read from parameter server: " << goal.target_pose.pose.position);
90 ROS_INFO(
"Exiting move goal Action Client");
ClMoveBaseZ * moveBaseClient_
void setGoal(const geometry_msgs::Pose &pose)
boost::optional< geometry_msgs::Point > goalPosition
virtual void onExit() override
boost::optional< float > goalYaw
void readStartPoseFromParameterServer(ClMoveBaseZ::Goal &goal)
CbNavigateGlobalPosition()
void setDefaultPlanners()
const std::string & getReferenceFrame() const
ISmaccState * getCurrentState()
ISmaccStateMachine * getStateMachine()
TComponent * getComponent()
void setGlobalSMData(std::string name, T value)
bool getParam(std::string param_name, T ¶m_storage)
void sendGoal(Goal &goal)