SMACC2
Loading...
Searching...
No Matches
cb_absolute_rotate.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
27
28#include <rclcpp/parameter_client.hpp>
29
30namespace cl_nav2z
31{
33CbAbsoluteRotate::CbAbsoluteRotate(float absoluteGoalAngleDegree, float yaw_goal_tolerance)
34{
35 this->absoluteGoalAngleDegree = absoluteGoalAngleDegree;
36
37 if (yaw_goal_tolerance >= 0)
38 {
39 this->yawGoalTolerance = yaw_goal_tolerance;
40 }
41}
42
44{
45 listener = std::make_shared<tf2_ros::Buffer>(getNode()->get_clock());
46 double goal_angle = this->absoluteGoalAngleDegree;
47
48 RCLCPP_INFO_STREAM(getLogger(), "[CbAbsoluteRotate] Absolute yaw Angle:" << goal_angle);
49
50 auto plannerSwitcher = this->nav2zClient_->getComponent<PlannerSwitcher>();
51 // this should work better with a coroutine and await
52 // this->plannerSwitcher_->setForwardPlanner();
53
55 {
56 plannerSwitcher->setPureSpinningPlanner();
57 }
58 else
59 {
60 plannerSwitcher->setDefaultPlanners();
61 }
62
64
66 auto referenceFrame = p->getReferenceFrame();
67 auto currentPoseMsg = p->toPoseMsg();
68
69 ClNav2Z::Goal goal;
70 goal.pose.header.frame_id = referenceFrame;
71 //goal.pose.header.stamp = getNode()->now();
72
73 auto targetAngle = goal_angle * M_PI / 180.0;
74 goal.pose.pose.position = currentPoseMsg.position;
75 tf2::Quaternion q;
76 q.setRPY(0, 0, targetAngle);
77 goal.pose.pose.orientation = tf2::toMsg(q);
78
80 if (odomTracker_ != nullptr)
81 {
82 auto pathname = this->getCurrentState()->getName() + " - " + getName();
83 odomTracker_->pushPath(pathname);
84 odomTracker_->setStartPoint(p->toPoseStampedMsg());
85 odomTracker_->setWorkingMode(odom_tracker::WorkingMode::RECORD_PATH);
86 }
87
88 auto goalCheckerSwitcher = nav2zClient_->getComponent<GoalCheckerSwitcher>();
89 goalCheckerSwitcher->setGoalCheckerId("absolute_rotate_goal_checker");
90
91 RCLCPP_INFO_STREAM(
92 getLogger(),
93 "[" << getName() << "] current pose yaw: " << tf2::getYaw(currentPoseMsg.orientation));
94 RCLCPP_INFO_STREAM(
95 getLogger(),
96 "[" << getName() << "] goal pose yaw: " << tf2::getYaw(goal.pose.pose.orientation));
97 this->sendGoal(goal);
98}
99
101{
102 auto log = this->getLogger();
103
104 std::string nodename = "/controller_server";
105
106 auto parameters_client =
107 std::make_shared<rclcpp::AsyncParametersClient>(this->getNode(), nodename);
108
109 RCLCPP_INFO_STREAM(
110 log, "[" << getName() << "] using a parameter client to update some controller parameters: "
111 << nodename << ". Waiting service.");
112 parameters_client->wait_for_service();
113
114 RCLCPP_INFO_STREAM(log, "[" << getName() << "] Service found: " << nodename << ".");
115
116 std::string localPlannerName;
117 std::vector<rclcpp::Parameter> parameters;
118
119 // dynamic_reconfigure::DoubleParameter yaw_goal_tolerance;
120 rclcpp::Parameter yaw_goal_tolerance("goal_checker.yaw_goal_tolerance");
121
122 rclcpp::Parameter max_vel_theta, min_vel_theta;
123
124 bool isRosBasePlanner = !spinningPlanner || *spinningPlanner == SpinningPlanner::Default;
125 bool isPureSpinningPlanner = spinningPlanner && *spinningPlanner == SpinningPlanner::PureSpinning;
126
127 // SELECTING CONTROLLER AND PARAMETERS NAME
128 if (isPureSpinningPlanner)
129 {
130 localPlannerName = "PureSpinningLocalPlanner";
131 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_angular_z_speed");
132 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta");
133 }
134 else if (isRosBasePlanner)
135 {
136 localPlannerName = "FollowPath";
137 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta");
138 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta");
139 }
140
141 if (!undo)
142 {
144 {
145 // save old yaw tolerance
146 auto fut = parameters_client->get_parameters(
147 {localPlannerName + ".yaw_goal_tolerance"},
148 [&](auto futureParameters)
149 {
150 auto params = futureParameters.get();
151 oldYawTolerance = params[0].as_double();
152 });
153
154 // make synchronous
155 fut.get();
156
157 yaw_goal_tolerance = rclcpp::Parameter("goal_checker.yaw_goal_tolerance", *yawGoalTolerance);
158 parameters.push_back(yaw_goal_tolerance);
159 RCLCPP_INFO_STREAM(
160 getLogger(), "[" << getName()
161 << "] updating yaw tolerance local planner to: " << *yawGoalTolerance
162 << ", from previous value: " << this->oldYawTolerance);
163 }
164
165 if (maxVelTheta)
166 {
167 if (isRosBasePlanner)
168 {
169 // nh.getParam(nodename + "/" + localPlannerName+"/min_vel_theta", oldMinVelTheta);
170 // getCurrentState()->getParam(nodename + "/" + localPlannerName + "/max_vel_theta", oldMaxVelTheta);
171
172 // save old yaw tolerance
173 auto fut = parameters_client->get_parameters(
174 {localPlannerName + ".max_vel_theta"},
175 [&](auto futureParameters)
176 {
177 auto params = futureParameters.get();
178 oldMaxVelTheta = params[0].as_double();
179 });
180
181 // make synchronous
182 fut.get();
183 }
184
185 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", *maxVelTheta);
186 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta", -*maxVelTheta);
187 parameters.push_back(max_vel_theta);
188 parameters.push_back(min_vel_theta);
189
190 RCLCPP_INFO_STREAM(
191 log, "[" << getName() << "] updating max vel theta local planner to: " << *maxVelTheta
192 << ", from previous value: " << this->oldMaxVelTheta);
193 RCLCPP_INFO_STREAM(
194 log, "[" << getName() << "] updating min vel theta local planner to: " << -*maxVelTheta
195 << ", from previous value: " << this->oldMinVelTheta);
196 }
197 }
198 else
199 {
201 {
202 yaw_goal_tolerance = rclcpp::Parameter("goal_checker.yaw_goal_tolerance", oldYawTolerance);
203 RCLCPP_INFO_STREAM(
204 log, "[" << getName() << "] restoring yaw tolerance local planner from: "
205 << *yawGoalTolerance << " , to previous value: " << this->oldYawTolerance);
206 }
207
208 if (maxVelTheta)
209 {
210 if (isRosBasePlanner)
211 {
212 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", oldMaxVelTheta);
213 min_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", oldMinVelTheta);
214 }
215
216 parameters.push_back(max_vel_theta);
217 parameters.push_back(min_vel_theta);
218 RCLCPP_INFO_STREAM(
219 log, "[" << getName() << "] restoring max vel theta local planner from: " << *maxVelTheta
220 << ", to previous value: " << this->oldMaxVelTheta);
221 RCLCPP_INFO_STREAM(
222 log, "[" << getName() << "] restoring min vel theta local planner from: " << -(*maxVelTheta)
223 << ", to previous value: " << this->oldMinVelTheta);
224 }
225 }
226
227 if (parameters.size())
228 {
229 std::stringstream ss;
230 ss << "Executing asynchronous request. Parameters to update: " << std::endl;
231 for (auto & p : parameters)
232 {
233 ss << p.get_name() << " - " << p.value_to_string() << std::endl;
234 }
235
236 RCLCPP_INFO_STREAM(getLogger(), "[CbAbsoluteRotate] " << ss.str());
237
238 auto futureResults = parameters_client->set_parameters(parameters);
239
240 int i = 0;
241 for (auto & res : futureResults.get())
242 {
243 RCLCPP_INFO_STREAM(
244 getLogger(), "[" << getName() << "] parameter result: " << parameters[i].get_name() << "="
245 << parameters[i].as_string() << ". Result: " << res.successful);
246 i++;
247 }
248
249 RCLCPP_INFO_STREAM(log, "[" << getName() << "] parameters updated");
250 }
251 else
252 {
253 RCLCPP_INFO_STREAM(log, "[" << getName() << "] skipping parameters update");
254 }
255}
256
258{
260 {
261 }
262 else
263 {
264 }
265
267}
268
269} // namespace cl_nav2z
std::optional< float > maxVelTheta
std::optional< SpinningPlanner > spinningPlanner
void updateTemporalBehaviorParameters(bool undo)
std::shared_ptr< tf2_ros::Buffer > listener
std::optional< float > yawGoalTolerance
void setGoalCheckerId(std::string goal_checker_id)
void setPureSpinningPlanner(bool commit=true)
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:76
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
TComponent * getComponent()
virtual std::string getName()=0