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 ******************************************************************************************************************/
20#include <cl_nav2z/common.hpp>
21
27
28namespace cl_nav2z
29{
30using namespace ::cl_nav2z::odom_tracker;
31using namespace smacc2;
32
34
36 float x, float y, float yaw, std::optional<CbNavigateGlobalPositionOptions> options)
37{
38 auto p = geometry_msgs::msg::Point();
39 p.x = x;
40 p.y = y;
41 goalPosition = p;
42 goalYaw = yaw;
43
44 if (options) this->options = *options;
45}
46
47void CbNavigateGlobalPosition::setGoal(const geometry_msgs::msg::Pose & pose)
48{
49 goalPosition = pose.position;
50 goalYaw = tf2::getYaw(pose.orientation);
51}
52
54{
55 RCLCPP_INFO(getLogger(), "Entering Navigate Global position");
56 RCLCPP_INFO(getLogger(), "Component requirements completed");
57
58 cl_nav2z::CpPose * cpPose;
59 this->requiresComponent(cpPose, ComponentRequirement::HARD);
60 auto pose = cpPose->toPoseMsg();
61
62 CpOdomTracker * odomTracker;
63 this->requiresComponent(odomTracker, ComponentRequirement::HARD);
64
65 CpPlannerSwitcher * plannerSwitcher;
66 this->requiresComponent(plannerSwitcher, ComponentRequirement::HARD);
67
68 plannerSwitcher->setDefaultPlanners(false);
69
71 {
72 plannerSwitcher->setDesiredController(*(options.controllerName_));
73 }
74
75 plannerSwitcher->commitPublish();
76
77 CpGoalCheckerSwitcher * goalCheckerSwitcher;
78 this->requiresComponent(goalCheckerSwitcher, ComponentRequirement::HARD);
79 goalCheckerSwitcher->setGoalCheckerId("goal_checker");
80
81 auto pathname = this->getCurrentState()->getName() + " - " + getName();
82 odomTracker->pushPath(pathname);
83 odomTracker->setStartPoint(pose);
84 odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);
85
86 execute();
87}
88
89// auxiliary function that defines the motion that is requested to the nav2 action server
91{
93 this->requiresComponent(p, ComponentRequirement::HARD);
94
95 auto referenceFrame = p->getReferenceFrame();
96 // auto currentPoseMsg = p->toPoseMsg();
97
98 RCLCPP_INFO(getLogger(), "Sending Goal to MoveBase");
99 nav2_msgs::action::NavigateToPose::Goal goal;
100 goal.pose.header.frame_id = referenceFrame;
101 //goal.pose.header.stamp = getNode()->now();
102
103 goal.pose.pose.position = goalPosition;
104 tf2::Quaternion q;
105 q.setRPY(0, 0, goalYaw);
106 goal.pose.pose.orientation = tf2::toMsg(q);
107
108 this->sendGoal(goal);
109}
110
111// This is the substate destructor. This code will be executed when the
112// workflow exits from this substate (that is according to statechart the moment when this object is destroyed)
114{
115 RCLCPP_INFO(getLogger(), "Exiting move goal Action Client");
116}
117
118} // namespace cl_nav2z
void sendGoal(nav2_msgs::action::NavigateToPose::Goal &goal)
void setGoal(const geometry_msgs::msg::Pose &pose)
void setGoalCheckerId(std::string goal_checker_id)
void setDefaultPlanners(bool commit=true)
geometry_msgs::msg::Pose toPoseMsg()
Definition cp_pose.hpp:57
const std::string & getReferenceFrame() const
Definition cp_pose.hpp:79
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
virtual std::string getName()=0