SMACC
Loading...
Searching...
No Matches
cb_navigate_global_position.cpp
Go to the documentation of this file.
5
6namespace cl_move_base_z
7{
8using namespace ::cl_move_base_z::odom_tracker;
9
11{
12}
13
15{
16 auto p = geometry_msgs::Point();
17 p.x = x;
18 p.y = y;
19 goalPosition = p;
20 goalYaw = yaw;
21}
22
23void CbNavigateGlobalPosition::setGoal(const geometry_msgs::Pose &pose)
24{
25 goalPosition = pose.position;
26 goalYaw = tf::getYaw(pose.orientation);
27}
28
30{
31 ROS_INFO("[CbNavigateGlobalPosition] Entering Navigate Global position");
32
33 auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();
34 plannerSwitcher->setDefaultPlanners();
35
36 auto pose = moveBaseClient_->getComponent<cl_move_base_z::Pose>()->toPoseMsg();
37 auto *odomTracker = moveBaseClient_->getComponent<OdomTracker>();
38
39 odomTracker->pushPath("FreeNavigationToGoalPose");
40 odomTracker->setStartPoint(pose);
41 odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);
42
43 execute();
44}
45
46// auxiliary function that defines the motion that is requested to the move_base action server
48{
50 auto referenceFrame = p->getReferenceFrame();
51 auto currentPoseMsg = p->toPoseMsg();
52
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();
58
59 // store the start pose on the state machine storage so that it can
60 // be referenced from other states (for example return to radial start)
61 this->getStateMachine()->setGlobalSMData("radial_start_pose", goal.target_pose);
62
64}
65
67{
68 if (!goalPosition)
69 {
70 this->getCurrentState()->getParam("start_position_x", goal.target_pose.pose.position.x);
71 this->getCurrentState()->getParam("start_position_y", goal.target_pose.pose.position.y);
72 double yaw;
73 this->getCurrentState()->getParam("start_position_yaw", yaw);
74
75 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
76 }
77 else
78 {
79 goal.target_pose.pose.position = *goalPosition;
80 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(*goalYaw);
81 }
82
83 ROS_INFO_STREAM("start position read from parameter server: " << goal.target_pose.pose.position);
84}
85
86// This is the substate destructor. This code will be executed when the
87// workflow exits from this substate (that is according to statechart the moment when this object is destroyed)
89{
90 ROS_INFO("Exiting move goal Action Client");
91}
92
93} // namespace cl_move_base_z
void setGoal(const geometry_msgs::Pose &pose)
boost::optional< geometry_msgs::Point > goalPosition
void readStartPoseFromParameterServer(ClMoveBaseZ::Goal &goal)
const std::string & getReferenceFrame() const
Definition: cp_pose.h:39
ISmaccStateMachine * getStateMachine()
TComponent * getComponent()
void setGlobalSMData(std::string name, T value)
bool getParam(std::string param_name, T &param_storage)