SMACC2
cb_navigate_global_position.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
21
27
28namespace cl_nav2z
29{
30using namespace ::cl_nav2z::odom_tracker;
31
33{
34 auto p = geometry_msgs::msg::Point();
35 p.x = x;
36 p.y = y;
37 goalPosition = p;
38 goalYaw = yaw;
39}
40
41void CbNavigateGlobalPosition::setGoal(const geometry_msgs::msg::Pose & pose)
42{
43 goalPosition = pose.position;
44 goalYaw = tf2::getYaw(pose.orientation);
45}
46
48{
49 RCLCPP_INFO(getLogger(), "Entering Navigate Global position");
50 RCLCPP_INFO(getLogger(), "Component requirements completed");
51
52 auto pose = moveBaseClient_->getComponent<cl_nav2z::Pose>()->toPoseMsg();
53 auto * odomTracker = moveBaseClient_->getComponent<OdomTracker>();
54
55 auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();
56 plannerSwitcher->setDefaultPlanners();
57
58 auto goalCheckerSwitcher = moveBaseClient_->getComponent<GoalCheckerSwitcher>();
59 goalCheckerSwitcher->setGoalCheckerId("goal_checker");
60
61 auto pathname = this->getCurrentState()->getName() + " - " + getName();
62 odomTracker->pushPath(pathname);
63 odomTracker->setStartPoint(pose);
64 odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);
65
66 execute();
67}
68
69// auxiliary function that defines the motion that is requested to the nav2 action server
71{
73 auto referenceFrame = p->getReferenceFrame();
74 // auto currentPoseMsg = p->toPoseMsg();
75
76 RCLCPP_INFO(getLogger(), "Sending Goal to MoveBase");
77 ClNav2Z::Goal goal;
78 goal.pose.header.frame_id = referenceFrame;
79 goal.pose.header.stamp = getNode()->now();
80
81 goal.pose.pose.position = goalPosition;
82 tf2::Quaternion q;
83 q.setRPY(0, 0, goalYaw);
84 goal.pose.pose.orientation = tf2::toMsg(q);
85 // store the start pose on the state machine storage so that it can
86 // be referenced from other states (for example return to radial start)
87 this->getStateMachine()->setGlobalSMData("radial_start_pose", goal.pose);
88
90}
91
92// This is the substate destructor. This code will be executed when the
93// workflow exits from this substate (that is according to statechart the moment when this object is destroyed)
95{
96 RCLCPP_INFO(getLogger(), "Exiting move goal Action Client");
97}
98
99} // namespace cl_nav2z
void setGoal(const geometry_msgs::msg::Pose &pose)
void setGoalCheckerId(std::string goal_checker_id)
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:77
virtual rclcpp::Node::SharedPtr getNode()
TComponent * getComponent()
void setGlobalSMData(std::string name, T value)
virtual std::string getName()=0
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)