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