SMACC2
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->moveBaseClient_->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 = moveBaseClient_->getComponent<GoalCheckerSwitcher>();
89 goalCheckerSwitcher->setGoalCheckerId("absolute_rotate_goal_checker");
90
91 RCLCPP_INFO_STREAM(
92 getLogger(),
93 "[CbAbsoluteRotate] current pose yaw: " << tf2::getYaw(currentPoseMsg.orientation));
94 RCLCPP_INFO_STREAM(
95 getLogger(), "[CbAbsoluteRotate] goal pose yaw: " << tf2::getYaw(goal.pose.pose.orientation));
97}
98
100{
101 auto log = this->getLogger();
102
103 std::string nodename = "/controller_server";
104
105 auto parameters_client =
106 std::make_shared<rclcpp::AsyncParametersClient>(this->getNode(), nodename);
107
108 RCLCPP_INFO_STREAM(
109 log, "[CbAbsoluteRotate] using a parameter client to update some controller parameters: "
110 << nodename << ". Waiting service.");
111 parameters_client->wait_for_service();
112
113 RCLCPP_INFO_STREAM(log, "[CbAbsoluteRotate] Service found: " << nodename << ".");
114
115 std::string localPlannerName;
116 std::vector<rclcpp::Parameter> parameters;
117
118 // dynamic_reconfigure::DoubleParameter yaw_goal_tolerance;
119 rclcpp::Parameter yaw_goal_tolerance("goal_checker.yaw_goal_tolerance");
120
121 rclcpp::Parameter max_vel_theta, min_vel_theta;
122
123 bool isRosBasePlanner = !spinningPlanner || *spinningPlanner == SpinningPlanner::Default;
124 bool isPureSpinningPlanner = spinningPlanner && *spinningPlanner == SpinningPlanner::PureSpinning;
125
126 // SELECTING CONTROLLER AND PARAMETERS NAME
127 if (isPureSpinningPlanner)
128 {
129 localPlannerName = "PureSpinningLocalPlanner";
130 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_angular_z_speed");
131 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta");
132 }
133 else if (isRosBasePlanner)
134 {
135 localPlannerName = "FollowPath";
136 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta");
137 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta");
138 }
139
140 if (!undo)
141 {
143 {
144 // save old yaw tolerance
145 auto fut = parameters_client->get_parameters(
146 {localPlannerName + ".yaw_goal_tolerance"}, [&](auto futureParameters) {
147 auto params = futureParameters.get();
148 oldYawTolerance = params[0].as_double();
149 });
150
151 // make synchronous
152 fut.get();
153
154 yaw_goal_tolerance = rclcpp::Parameter("goal_checker.yaw_goal_tolerance", *yawGoalTolerance);
155 parameters.push_back(yaw_goal_tolerance);
156 RCLCPP_INFO(
157 getLogger(),
158 "[CbAbsoluteRotate] updating yaw tolerance local planner to: %lf, from previous value: "
159 "%lf ",
161 }
162
163 if (maxVelTheta)
164 {
165 if (isRosBasePlanner)
166 {
167 // nh.getParam(nodename + "/" + localPlannerName+"/min_vel_theta", oldMinVelTheta);
168 // getCurrentState()->getParam(nodename + "/" + localPlannerName + "/max_vel_theta", oldMaxVelTheta);
169
170 // save old yaw tolerance
171 auto fut = parameters_client->get_parameters(
172 {localPlannerName + ".max_vel_theta"}, [&](auto futureParameters) {
173 auto params = futureParameters.get();
174 oldMaxVelTheta = params[0].as_double();
175 });
176
177 // make synchronous
178 fut.get();
179 }
180
181 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", *maxVelTheta);
182 min_vel_theta = rclcpp::Parameter(localPlannerName + ".min_vel_theta", -*maxVelTheta);
183 parameters.push_back(max_vel_theta);
184 parameters.push_back(min_vel_theta);
185
186 RCLCPP_INFO(
187 log,
188 "[CbAbsoluteRotate] updating max vel theta local planner to: %lf, from previous value: "
189 "%lf ",
191 RCLCPP_INFO(
192 log,
193 "[CbAbsoluteRotate] updating min vel theta local planner to: %lf, from previous value: "
194 "%lf ",
195 -*maxVelTheta, this->oldMinVelTheta);
196 }
197 }
198 else
199 {
201 {
202 yaw_goal_tolerance = rclcpp::Parameter("goal_checker.yaw_goal_tolerance", oldYawTolerance);
203 RCLCPP_INFO(
204 log,
205 "[CbAbsoluteRotate] restoring yaw tolerance local planner from: %lf, to previous value: "
206 "%lf ",
208 }
209
210 if (maxVelTheta)
211 {
212 if (isRosBasePlanner)
213 {
214 max_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", oldMaxVelTheta);
215 min_vel_theta = rclcpp::Parameter(localPlannerName + ".max_vel_theta", oldMinVelTheta);
216 }
217
218 parameters.push_back(max_vel_theta);
219 parameters.push_back(min_vel_theta);
220 RCLCPP_INFO(
221 log,
222 "[CbAbsoluteRotate] restoring max vel theta local planner from: %lf, to previous value: "
223 "%lf ",
225 RCLCPP_INFO(
226 log,
227 "[CbAbsoluteRotate] restoring min vel theta local planner from: %lf, to previous value: "
228 "%lf ",
229 -(*maxVelTheta), this->oldMinVelTheta);
230 }
231 }
232
233 if (parameters.size())
234 {
235 std::stringstream ss;
236 ss << "Executing asynchronous request. Parameters to update: " << std::endl;
237 for (auto & p : parameters)
238 {
239 ss << p.get_name() << " - " << p.value_to_string() << std::endl;
240 }
241
242 RCLCPP_INFO_STREAM(getLogger(), "[CbAbsoluteRotate] " << ss.str());
243
244 auto futureResults = parameters_client->set_parameters(parameters);
245
246 int i = 0;
247 for (auto & res : futureResults.get())
248 {
249 RCLCPP_INFO_STREAM(
250 getLogger(), "[CbAbsoluteRotate] parameter result: " << parameters[i].get_name() << "="
251 << parameters[i].as_string()
252 << ". Result: " << res.successful);
253 i++;
254 }
255
256 RCLCPP_INFO(log, "[CbAbsoluteRotate] parameters updated");
257 }
258 else
259 {
260 RCLCPP_INFO(log, "[CbAbsoluteRotate] skipping parameters update");
261 }
262}
263
265{
267 {
268 }
269 else
270 {
271 }
272
274}
275
276} // 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)
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:77
virtual rclcpp::Node::SharedPtr getNode()
TComponent * getComponent()
virtual std::string getName()=0
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)