SMACC2
odom_tracker.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
22#include <angles/angles.h>
23#include <tf2/utils.h>
25
26#include <boost/range/adaptor/reversed.hpp>
27
28namespace cl_nav2z
29{
30namespace odom_tracker
31{
32OdomTracker::OdomTracker(std::string odomTopicName, std::string odomFrame)
33{
35 publishMessages = true;
37 odomFrame_ = odomFrame;
38 odomTopicName_ = odomTopicName;
39}
40
41template <typename T>
43 rclcpp::Node::SharedPtr & node, std::string param_name, T & value)
44{
45 if (!node->get_parameter(param_name, value))
46 {
47 RCLCPP_INFO_STREAM(node->get_logger(), "[OdomTracker] autoset " << param_name << ": " << value);
48 node->declare_parameter(param_name, value);
49 }
50 else
51 {
52 RCLCPP_INFO_STREAM(node->get_logger(), "[OdomTracker] " << param_name << ": " << value);
53 }
54}
55
57{
58 // default values
59 recordPointDistanceThreshold_ = 0.005; // 5 mm
60 recordAngularDistanceThreshold_ = 0.1; // radians
61 clearPointDistanceThreshold_ = 0.05; // 5 cm
63
64 auto nh = getNode();
65 RCLCPP_WARN(getLogger(), "[OdomTracker] Initializing Odometry Tracker");
66
67 parameterDeclareAndtryGetOrSet(nh, "odom_frame", this->odomFrame_);
69 nh, "record_point_distance_threshold", recordPointDistanceThreshold_);
71 nh, "record_angular_distance_threshold", recordAngularDistanceThreshold_);
73 nh, "clear_point_distance_threshold", clearPointDistanceThreshold_);
75 nh, "clear_angular_distance_threshold", clearAngularDistanceThreshold_);
76
78 {
79 rclcpp::SensorDataQoS qos;
80 odomSub_ = nh->create_subscription<nav_msgs::msg::Odometry>(
81 odomTopicName_, qos,
82 std::bind(&OdomTracker::processOdometryMessage, this, std::placeholders::_1));
83 }
84
85 robotBasePathPub_ = nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_path", 1);
87 nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_stacked_path", 1);
88}
89
96{
97 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
98 std::lock_guard<std::mutex> lock(m_mutex_);
99
100 switch (workingMode)
101 {
103 RCLCPP_INFO_STREAM(
104 getLogger(),
105 "[OdomTracker] setting working mode to RECORD - record_point_distance_threshold: "
107 << ", record_angular_distance_threshold: " << recordAngularDistanceThreshold_);
108 break;
110 RCLCPP_INFO_STREAM(
111 getLogger(),
112 "[OdomTracker] setting working mode to CLEAR - clear_point_distance_threshold: "
114 << ", clear_angular_distance_threshold: " << clearAngularDistanceThreshold_);
115 break;
117 RCLCPP_INFO_STREAM(getLogger(), "[OdomTracker] setting working mode to IDLE");
118 break;
119 default:
120
121 RCLCPP_INFO_STREAM(getLogger(), "[OdomTracker] setting working mode to <UNKNOWN>");
122 }
123
124 workingMode_ = workingMode;
125 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
126}
127
134{
135 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
136 std::lock_guard<std::mutex> lock(m_mutex_);
137 publishMessages = value;
138 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
140}
141
142void OdomTracker::pushPath() { this->pushPath(std::string()); }
143
144void OdomTracker::pushPath(std::string pathname)
145{
146 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire");
147 std::lock_guard<std::mutex> lock(m_mutex_);
148 RCLCPP_INFO(getLogger(), "PUSH_PATH PATH EXITTING");
149 this->logStateString();
150
152 pathStack_.push_back(baseTrajectory_);
153
154 currentPathName_ = pathname;
155
156 // clean the current trajectory to start a new one
157 baseTrajectory_.poses.clear();
158
159 RCLCPP_INFO(getLogger(), "PUSH_PATH PATH EXITTING");
160 this->logStateString();
161 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex release");
163
164 this->currentMotionGoal_.reset();
165}
166
167void OdomTracker::popPath(int popCount, bool keepPreviousPath)
168{
169 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire");
170 std::lock_guard<std::mutex> lock(m_mutex_);
171
172 RCLCPP_INFO(getLogger(), "POP PATH ENTRY");
173 this->logStateString();
174
175 if (!keepPreviousPath)
176 {
177 baseTrajectory_.poses.clear();
178 }
179
180 while (popCount > 0 && !pathStack_.empty())
181 {
182 auto & stackedPath = pathStack_.back().poses;
183 auto & stackedPathInfo = pathInfos_.back();
184
185 baseTrajectory_.poses.insert(
186 baseTrajectory_.poses.begin(), stackedPath.begin(), stackedPath.end());
187 this->currentMotionGoal_ = stackedPathInfo.goalPose;
188 pathStack_.pop_back();
189 pathInfos_.pop_back();
190 popCount--;
191
192 RCLCPP_INFO(getLogger(), "POP PATH Iteration ");
193 this->logStateString();
194 }
195
196 RCLCPP_INFO(getLogger(), "POP PATH EXITING");
197 this->logStateString();
198 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex release");
200
201 this->currentMotionGoal_.reset();
202}
203
205{
206 std::stringstream ss;
207 ss << "--- odom tracker state ---" << std::endl;
208 ss
209 << " - path stack -" << currentPathName_ << " - size:"
210 << pathStack_.size()
211 //<< " goal: " << (getCurrentMotionGoal()? getCurrentMotionGoal()->pose: geometry_msgs::msg::Pose())
212 << std::endl;
213 ss << " - [STACK-HEAD active path size: " << baseTrajectory_.poses.size() << "]" << std::endl;
214 int i = 0;
215 for (auto & p : pathStack_ | boost::adaptors::reversed)
216 {
217 auto & pathinfo = pathInfos_[pathInfos_.size() - i - 1];
218 std::string goalstr = "[]";
219 if (pathinfo.goalPose)
220 {
221 std::stringstream ss;
222 ss << *(pathinfo.goalPose);
223 goalstr = ss.str();
224 }
225
226 ss << " - p " << i << "[" << p.header.stamp << "], size: " << p.poses.size() << " - "
227 << pathinfo.name << " - goal: " << goalstr << std::endl;
228 i++;
229 }
230 ss << "---";
231 RCLCPP_INFO(getLogger(), ss.str().c_str());
232}
233
235{
236 std::lock_guard<std::mutex> lock(m_mutex_);
237 baseTrajectory_.poses.clear();
238
239 rtPublishPaths(getNode()->now());
240 this->logStateString();
242
243 this->currentMotionGoal_.reset();
244}
245
246void OdomTracker::setCurrentPathName(const std::string & currentPathName)
247{
248 currentPathName_ = currentPathName;
249}
250
251void OdomTracker::setStartPoint(const geometry_msgs::msg::PoseStamped & pose)
252{
253 std::lock_guard<std::mutex> lock(m_mutex_);
254 RCLCPP_INFO_STREAM(getLogger(), "[OdomTracker] set current path starting point: " << pose);
255 if (baseTrajectory_.poses.size() > 0)
256 {
257 baseTrajectory_.poses[0] = pose;
258 }
259 else
260 {
261 baseTrajectory_.poses.push_back(pose);
262 }
264}
265
266void OdomTracker::setStartPoint(const geometry_msgs::msg::Pose & pose)
267{
268 std::lock_guard<std::mutex> lock(m_mutex_);
269 RCLCPP_INFO_STREAM(getLogger(), "[OdomTracker] set current path starting point: " << pose);
270 geometry_msgs::msg::PoseStamped posestamped;
271 posestamped.header.frame_id = this->odomFrame_;
272 posestamped.header.stamp = getNode()->now();
273 posestamped.pose = pose;
274
275 if (baseTrajectory_.poses.size() > 0)
276 {
277 baseTrajectory_.poses[0] = posestamped;
278 }
279 else
280 {
281 baseTrajectory_.poses.push_back(posestamped);
282 }
284}
285
286void OdomTracker::setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped & pose)
287{
288 std::lock_guard<std::mutex> lock(m_mutex_);
289 this->currentMotionGoal_ = pose;
290}
291
292std::optional<geometry_msgs::msg::PoseStamped> OdomTracker::getCurrentMotionGoal()
293{
294 std::lock_guard<std::mutex> lock(m_mutex_);
295 return this->currentMotionGoal_;
296}
297
298nav_msgs::msg::Path OdomTracker::getPath()
299{
300 std::lock_guard<std::mutex> lock(m_mutex_);
301 return this->baseTrajectory_;
302}
303
309void OdomTracker::rtPublishPaths(rclcpp::Time timestamp)
310{
311 baseTrajectory_.header.stamp = timestamp;
313
314 aggregatedStackPathMsg_.header.stamp = timestamp;
316}
317
319{
320 aggregatedStackPathMsg_.poses.clear();
321 for (auto & p : pathStack_)
322 {
323 aggregatedStackPathMsg_.poses.insert(
324 aggregatedStackPathMsg_.poses.end(), p.poses.begin(), p.poses.end());
325 }
326
327 aggregatedStackPathMsg_.header.frame_id = this->odomFrame_;
328}
329
335bool OdomTracker::updateClearPath(const nav_msgs::msg::Odometry & odom)
336{
337 // we initially accept any message if the queue is empty
339 geometry_msgs::msg::PoseStamped base_pose;
340
341 base_pose.pose = odom.pose.pose;
342 base_pose.header = odom.header;
343 baseTrajectory_.header = odom.header;
344
345 bool acceptBackward = false;
346 bool clearingError = false;
347 bool finished = false;
348
349 while (!finished)
350 {
351 if (
352 baseTrajectory_.poses.size() <=
353 1) // we at least keep always the first point of the forward path when clearing
354 // (this is important for backwards planner replanning and not losing the
355 // last goal)
356 {
357 acceptBackward = false;
358 finished = true;
359 }
360 else
361 {
362 auto & carrotPose = baseTrajectory_.poses.back().pose;
363 auto & carrotPoint = carrotPose.position;
364
365 double carrotAngle = tf2::getYaw(carrotPose.orientation);
366
367 auto & currePose = base_pose.pose;
368 auto & currePoint = currePose.position;
369 double currentAngle = tf2::getYaw(currePose.orientation);
370
371 double lastpointdist = p2pDistance(carrotPoint, currePoint);
372 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
373
374 acceptBackward = !baseTrajectory_.poses.empty() &&
375 lastpointdist < clearPointDistanceThreshold_ &&
376 goalAngleOffset < clearAngularDistanceThreshold_;
377
378 clearingError = lastpointdist > 2 * clearPointDistanceThreshold_;
379 RCLCPP_DEBUG_STREAM(
380 getLogger(), "[OdomTracker] clearing (accepted: " << acceptBackward
381 << ") linerr: " << lastpointdist
382 << ", anglerr: " << goalAngleOffset);
383 }
384
385 // RCLCPP_INFO(getLogger(),"Backwards, last distance: %lf < %lf accept: %d", dist,
386 // minPointDistanceBackwardThresh_, acceptBackward);
387 if (
388 acceptBackward &&
389 baseTrajectory_.poses.size() > 1) /* we always leave at least one item, specially interesting
390 for the backward local planner reach the backwards goal
391 with enough precision*/
392 {
393 baseTrajectory_.poses.pop_back();
394 }
395 else if (clearingError)
396 {
397 finished = true;
398 RCLCPP_WARN(getLogger(), "[OdomTracker] Incorrect odom clearing motion.");
399 }
400 else
401 {
402 finished = true;
404 }
405 }
406
407 return acceptBackward;
408}
414bool OdomTracker::updateRecordPath(const nav_msgs::msg::Odometry & odom)
415{
417 geometry_msgs::msg::PoseStamped base_pose;
418
419 base_pose.pose = odom.pose.pose;
420 base_pose.header = odom.header;
421 baseTrajectory_.header = odom.header;
422
423 bool enqueueOdomMessage = false;
424
425 double dist = -1;
426 if (baseTrajectory_.poses.empty())
427 {
428 enqueueOdomMessage = true;
429 }
430 else
431 {
432 const auto & prevPose = baseTrajectory_.poses.back().pose;
433 const geometry_msgs::msg::Point & prevPoint = prevPose.position;
434 double prevAngle = tf2::getYaw(prevPose.orientation);
435
436 const geometry_msgs::msg::Point & currePoint = base_pose.pose.position;
437 double currentAngle = tf2::getYaw(base_pose.pose.orientation);
438
439 dist = p2pDistance(prevPoint, currePoint);
440 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
441
442 // RCLCPP_WARN(getLogger(),"dist %lf vs min %lf", dist, recordPointDistanceThreshold_);
443
445 {
446 enqueueOdomMessage = true;
447 }
448 else
449 {
450 // RCLCPP_WARN(getLogger(),"skip odom, dist: %lf", dist);
451 enqueueOdomMessage = false;
452 }
453 }
454
455 if (enqueueOdomMessage)
456 {
457 baseTrajectory_.poses.push_back(base_pose);
458 }
459
460 return enqueueOdomMessage;
461}
462
469{
470 if (!getNode()->get_parameter("odom_frame", this->odomFrame_))
471 {
472 }
473
474 if (!getNode()->get_parameter("record_point_distance_threshold", recordPointDistanceThreshold_))
475 {
476 }
477
478 if (!getNode()->get_parameter(
479 "record_angular_distance_threshold", recordAngularDistanceThreshold_))
480 {
481 }
482
483 if (!getNode()->get_parameter("clear_point_distance_threshold", clearPointDistanceThreshold_))
484 {
485 }
486
487 if (!getNode()->get_parameter("clear_angular_distance_threshold", clearAngularDistanceThreshold_))
488 {
489 }
490}
491
497void OdomTracker::processOdometryMessage(const nav_msgs::msg::Odometry::SharedPtr odom)
498{
499 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
500 std::lock_guard<std::mutex> lock(m_mutex_);
501
503
505 {
506 updateRecordPath(*odom);
507 }
509 {
510 updateClearPath(*odom);
511 }
512
513 // RCLCPP_WARN(getLogger(),"odomTracker odometry callback");
514 if (publishMessages)
515 {
516 rtPublishPaths(odom->header.stamp);
517 }
518
519 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
520}
521} // namespace odom_tracker
522} // namespace cl_nav2z
void setCurrentPathName(const std::string &currentPathName)
void setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped &pose)
virtual void rtPublishPaths(rclcpp::Time timestamp)
double recordPointDistanceThreshold_
How much distance there is between two points of the path.
virtual bool updateClearPath(const nav_msgs::msg::Odometry &odom)
std::optional< geometry_msgs::msg::PoseStamped > currentMotionGoal_
OdomTracker(std::string odomtopicName="/odom", std::string odomFrame="odom")
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathPub_
nav_msgs::msg::Path baseTrajectory_
Processed path for the mouth of the reel.
void setWorkingMode(WorkingMode workingMode)
std::vector< nav_msgs::msg::Path > pathStack_
void popPath(int pathCount=1, bool keepPreviousPath=false)
virtual void processOdometryMessage(const nav_msgs::msg::Odometry::SharedPtr odom)
odom callback: Updates the path - this must be called periodically for each odometry message.
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
nav_msgs::msg::Path aggregatedStackPathMsg_
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odomSub_
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathStackedPub_
virtual bool updateRecordPath(const nav_msgs::msg::Odometry &odom)
std::optional< geometry_msgs::msg::PoseStamped > getCurrentMotionGoal()
std::vector< PathInfo > pathInfos_
rclcpp::Logger getLogger()
rclcpp::Node::SharedPtr getNode()
double p2pDistance(const geometry_msgs::msg::Point &p1, const geometry_msgs::msg::Point &p2)
void parameterDeclareAndtryGetOrSet(rclcpp::Node::SharedPtr &node, std::string param_name, T &value)