SMACC2
Loading...
Searching...
No Matches
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
35 float x, float y, float yaw, std::optional<CbNavigateGlobalPositionOptions> options)
36{
37 auto p = geometry_msgs::msg::Point();
38 p.x = x;
39 p.y = y;
40 goalPosition = p;
41 goalYaw = yaw;
42
43 if (options) this->options = *options;
44}
45
46void CbNavigateGlobalPosition::setGoal(const geometry_msgs::msg::Pose & pose)
47{
48 goalPosition = pose.position;
49 goalYaw = tf2::getYaw(pose.orientation);
50}
51
53{
54 RCLCPP_INFO(getLogger(), "Entering Navigate Global position");
55 RCLCPP_INFO(getLogger(), "Component requirements completed");
56
57 auto pose = nav2zClient_->getComponent<cl_nav2z::Pose>()->toPoseMsg();
58 auto * odomTracker = nav2zClient_->getComponent<OdomTracker>();
59
60 auto plannerSwitcher = nav2zClient_->getComponent<PlannerSwitcher>();
61
62 plannerSwitcher->setDefaultPlanners(false);
63
65 {
66 plannerSwitcher->setDesiredController(*(options.controllerName_));
67 }
68
69 plannerSwitcher->commitPublish();
70
71 auto goalCheckerSwitcher = nav2zClient_->getComponent<GoalCheckerSwitcher>();
72 goalCheckerSwitcher->setGoalCheckerId("goal_checker");
73
74 auto pathname = this->getCurrentState()->getName() + " - " + getName();
75 odomTracker->pushPath(pathname);
76 odomTracker->setStartPoint(pose);
77 odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);
78
79 execute();
80}
81
82// auxiliary function that defines the motion that is requested to the nav2 action server
84{
86 auto referenceFrame = p->getReferenceFrame();
87 // auto currentPoseMsg = p->toPoseMsg();
88
89 RCLCPP_INFO(getLogger(), "Sending Goal to MoveBase");
90 ClNav2Z::Goal goal;
91 goal.pose.header.frame_id = referenceFrame;
92 //goal.pose.header.stamp = getNode()->now();
93
94 goal.pose.pose.position = goalPosition;
95 tf2::Quaternion q;
96 q.setRPY(0, 0, goalYaw);
97 goal.pose.pose.orientation = tf2::toMsg(q);
98
99 this->sendGoal(goal);
100}
101
102// This is the substate destructor. This code will be executed when the
103// workflow exits from this substate (that is according to statechart the moment when this object is destroyed)
105{
106 RCLCPP_INFO(getLogger(), "Exiting move goal Action Client");
107}
108
109} // 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:76
virtual rclcpp::Logger getLogger() const
TComponent * getComponent()
virtual std::string getName()=0