SMACC2
Loading...
Searching...
No Matches
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_INFO_STREAM(
80 nh->get_logger(), "[OdomTracker] subscribing to odom topic: " << odomTopicName_);
81
82 rclcpp::SensorDataQoS qos;
83 odomSub_ = nh->create_subscription<nav_msgs::msg::Odometry>(
84 odomTopicName_, qos,
85 std::bind(&OdomTracker::processOdometryMessage, this, std::placeholders::_1));
86 }
87
88 robotBasePathPub_ = nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_path", 1);
90 nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_stacked_path", 1);
91}
92
99{
100 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
101 std::lock_guard<std::mutex> lock(m_mutex_);
102
103 switch (workingMode)
104 {
106 RCLCPP_INFO_STREAM(
107 getLogger(),
108 "[OdomTracker] setting working mode to RECORD - record_point_distance_threshold: "
110 << ", record_angular_distance_threshold: " << recordAngularDistanceThreshold_);
111 break;
113 RCLCPP_INFO_STREAM(
114 getLogger(),
115 "[OdomTracker] setting working mode to CLEAR - clear_point_distance_threshold: "
117 << ", clear_angular_distance_threshold: " << clearAngularDistanceThreshold_);
118 break;
120 RCLCPP_INFO_STREAM(getLogger(), "[OdomTracker] setting working mode to IDLE");
121 break;
122 default:
123
124 RCLCPP_INFO_STREAM(getLogger(), "[OdomTracker] setting working mode to <UNKNOWN>");
125 }
126
127 workingMode_ = workingMode;
128 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
129}
130
137{
138 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
139 std::lock_guard<std::mutex> lock(m_mutex_);
140 publishMessages = value;
141 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
143}
144
145void OdomTracker::pushPath() { this->pushPath(std::string()); }
146
147void OdomTracker::pushPath(std::string pathname)
148{
149 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire");
150 std::lock_guard<std::mutex> lock(m_mutex_);
151 this->logStateString(false);
152
154 pathStack_.push_back(baseTrajectory_);
155
156 geometry_msgs::msg::PoseStamped goalPose;
157 if (this->currentMotionGoal_) goalPose = *this->currentMotionGoal_;
158
159 RCLCPP_INFO_STREAM(
160 getLogger(), "[OdomTracker] currentPathName: " << pathname
161 << " size: " << baseTrajectory_.poses.size()
162 << " current motion goal: " << goalPose);
163
164 currentPathName_ = pathname;
165
166 // clean the current trajectory to start a new one
167 baseTrajectory_.poses.clear();
168
169 this->logStateString(false);
171
172 this->currentMotionGoal_.reset();
173}
174
175void OdomTracker::popPath(int popCount, bool keepPreviousPath)
176{
177 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire");
178 std::lock_guard<std::mutex> lock(m_mutex_);
179
180 RCLCPP_INFO(getLogger(), "POP PATH ENTRY");
181 this->logStateString();
182
183 if (!keepPreviousPath)
184 {
185 baseTrajectory_.poses.clear();
186 }
187
188 while (popCount > 0 && !pathStack_.empty())
189 {
190 auto & stackedPath = pathStack_.back().poses;
191 auto & stackedPathInfo = pathInfos_.back();
192
193 baseTrajectory_.poses.insert(
194 baseTrajectory_.poses.begin(), stackedPath.begin(), stackedPath.end());
195 this->currentMotionGoal_ = stackedPathInfo.goalPose;
196 pathStack_.pop_back();
197 pathInfos_.pop_back();
198 popCount--;
199
200 RCLCPP_INFO(getLogger(), "POP PATH Iteration ");
201 this->logStateString();
202 }
203
204 RCLCPP_INFO(getLogger(), "POP PATH EXITING");
205 this->logStateString();
206 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex release");
208
209 this->currentMotionGoal_.reset();
210}
211
213{
214 std::stringstream ss;
215 ss << "--- odom tracker state ---" << std::endl;
216 ss
217 << " - path stack -" << currentPathName_ << " - size:"
218 << pathStack_.size()
219 //<< " goal: " << (getCurrentMotionGoal()? getCurrentMotionGoal()->pose: geometry_msgs::msg::Pose())
220 << std::endl;
221 ss << " - [STACK-HEAD active path size: " << baseTrajectory_.poses.size() << "]" << std::endl;
222 int i = 0;
223 for (auto & p : pathStack_ | boost::adaptors::reversed)
224 {
225 auto & pathinfo = pathInfos_[pathInfos_.size() - i - 1];
226 std::string goalstr = "[]";
227 if (pathinfo.goalPose)
228 {
229 std::stringstream ss;
230 ss << *(pathinfo.goalPose);
231 goalstr = ss.str();
232 }
233
234 ss << " - p " << i << "[" << p.header.stamp << "], size: " << p.poses.size() << " - "
235 << pathinfo.name << " - goal: " << goalstr << std::endl;
236 i++;
237 }
238 ss << "---";
239
240 if (debug)
241 RCLCPP_DEBUG(getLogger(), ss.str().c_str());
242 else
243 RCLCPP_INFO(getLogger(), ss.str().c_str());
244}
245
247{
248 std::lock_guard<std::mutex> lock(m_mutex_);
249 baseTrajectory_.poses.clear();
250
251 rtPublishPaths(getNode()->now());
252 this->logStateString();
254
255 this->currentMotionGoal_.reset();
256}
257
258void OdomTracker::setCurrentPathName(const std::string & currentPathName)
259{
260 currentPathName_ = currentPathName;
261}
262
263void OdomTracker::setStartPoint(const geometry_msgs::msg::PoseStamped & pose)
264{
265 std::lock_guard<std::mutex> lock(m_mutex_);
266 RCLCPP_INFO_STREAM(getLogger(), "[OdomTracker] set current path starting point: " << pose);
267 if (baseTrajectory_.poses.size() > 0)
268 {
269 baseTrajectory_.poses[0] = pose;
270 }
271 else
272 {
273 baseTrajectory_.poses.push_back(pose);
274 }
276}
277
278void OdomTracker::setStartPoint(const geometry_msgs::msg::Pose & pose)
279{
280 std::lock_guard<std::mutex> lock(m_mutex_);
281 RCLCPP_INFO_STREAM(getLogger(), "[OdomTracker] set current path starting point: " << pose);
282 geometry_msgs::msg::PoseStamped posestamped;
283 posestamped.header.frame_id = this->odomFrame_;
284 posestamped.header.stamp = getNode()->now();
285 posestamped.pose = pose;
286
287 if (baseTrajectory_.poses.size() > 0)
288 {
289 baseTrajectory_.poses[0] = posestamped;
290 }
291 else
292 {
293 baseTrajectory_.poses.push_back(posestamped);
294 }
296}
297
298void OdomTracker::setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped & pose)
299{
300 std::lock_guard<std::mutex> lock(m_mutex_);
301 this->currentMotionGoal_ = pose;
302}
303
304std::optional<geometry_msgs::msg::PoseStamped> OdomTracker::getCurrentMotionGoal()
305{
306 std::lock_guard<std::mutex> lock(m_mutex_);
307 return this->currentMotionGoal_;
308}
309
310nav_msgs::msg::Path OdomTracker::getPath()
311{
312 std::lock_guard<std::mutex> lock(m_mutex_);
313 return this->baseTrajectory_;
314}
315
321void OdomTracker::rtPublishPaths(rclcpp::Time timestamp)
322{
323 baseTrajectory_.header.stamp = timestamp;
325
326 aggregatedStackPathMsg_.header.stamp = timestamp;
328}
329
331{
332 aggregatedStackPathMsg_.poses.clear();
333 for (auto & p : pathStack_)
334 {
335 aggregatedStackPathMsg_.poses.insert(
336 aggregatedStackPathMsg_.poses.end(), p.poses.begin(), p.poses.end());
337 }
338
339 aggregatedStackPathMsg_.header.frame_id = this->odomFrame_;
340}
341
347bool OdomTracker::updateClearPath(const nav_msgs::msg::Odometry & odom)
348{
349 // we initially accept any message if the queue is empty
351 geometry_msgs::msg::PoseStamped base_pose;
352
353 base_pose.pose = odom.pose.pose;
354 base_pose.header = odom.header;
355 baseTrajectory_.header = odom.header;
356
357 bool acceptBackward = false;
358 bool clearingError = false;
359 bool finished = false;
360
361 while (!finished)
362 {
363 if (
364 baseTrajectory_.poses.size() <=
365 1) // we at least keep always the first point of the forward path when clearing
366 // (this is important for backwards planner replanning and not losing the
367 // last goal)
368 {
369 acceptBackward = false;
370 finished = true;
371 }
372 else
373 {
374 auto & carrotPose = baseTrajectory_.poses.back().pose;
375 auto & carrotPoint = carrotPose.position;
376
377 double carrotAngle = tf2::getYaw(carrotPose.orientation);
378
379 auto & currePose = base_pose.pose;
380 auto & currePoint = currePose.position;
381 double currentAngle = tf2::getYaw(currePose.orientation);
382
383 double lastpointdist = p2pDistance(carrotPoint, currePoint);
384 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
385
386 acceptBackward = !baseTrajectory_.poses.empty() &&
387 lastpointdist < clearPointDistanceThreshold_ &&
388 goalAngleOffset < clearAngularDistanceThreshold_;
389
390 clearingError = lastpointdist > 2 * clearPointDistanceThreshold_;
391 RCLCPP_DEBUG_STREAM(
392 getLogger(), "[OdomTracker] clearing (accepted: " << acceptBackward
393 << ") linerr: " << lastpointdist
394 << ", anglerr: " << goalAngleOffset);
395 }
396
397 // RCLCPP_INFO(getLogger(),"Backwards, last distance: %lf < %lf accept: %d", dist,
398 // minPointDistanceBackwardThresh_, acceptBackward);
399 if (
400 acceptBackward &&
401 baseTrajectory_.poses.size() > 1) /* we always leave at least one item, specially interesting
402 for the backward local planner reach
403 the backwards goal with enough precision*/
404 {
405 baseTrajectory_.poses.pop_back();
406 }
407 else if (clearingError)
408 {
409 finished = true;
410 RCLCPP_WARN(getLogger(), "[OdomTracker] Incorrect odom clearing motion.");
411 }
412 else
413 {
414 finished = true;
416 }
417 }
418
419 return acceptBackward;
420}
426bool OdomTracker::updateRecordPath(const nav_msgs::msg::Odometry & odom)
427{
429 geometry_msgs::msg::PoseStamped base_pose;
430
431 base_pose.pose = odom.pose.pose;
432 base_pose.header = odom.header;
433 baseTrajectory_.header = odom.header;
434
435 bool enqueueOdomMessage = false;
436
437 double dist = -1;
438 if (baseTrajectory_.poses.empty())
439 {
440 enqueueOdomMessage = true;
441 }
442 else
443 {
444 const auto & prevPose = baseTrajectory_.poses.back().pose;
445 const geometry_msgs::msg::Point & prevPoint = prevPose.position;
446 double prevAngle = tf2::getYaw(prevPose.orientation);
447
448 const geometry_msgs::msg::Point & currePoint = base_pose.pose.position;
449 double currentAngle = tf2::getYaw(base_pose.pose.orientation);
450
451 dist = p2pDistance(prevPoint, currePoint);
452 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
453
454 // RCLCPP_WARN(getLogger(),"dist %lf vs min %lf", dist, recordPointDistanceThreshold_);
455
456 RCLCPP_WARN_THROTTLE(getLogger(), *getNode()->get_clock(), 2000, "odom received");
457
459 {
460 enqueueOdomMessage = true;
461 }
462 else
463 {
464 // RCLCPP_WARN(getLogger(),"skip odom, dist: %lf", dist);
465 enqueueOdomMessage = false;
466 }
467 }
468
469 if (enqueueOdomMessage)
470 {
471 RCLCPP_WARN_THROTTLE(
472 getLogger(), *getNode()->get_clock(), 2000, "enqueue odom tracker pose. dist %lf vs min %lf",
474 baseTrajectory_.poses.push_back(base_pose);
475 }
476
477 return enqueueOdomMessage;
478}
479
486{
487 if (!getNode()->get_parameter("odom_frame", this->odomFrame_))
488 {
489 }
490
491 if (!getNode()->get_parameter("record_point_distance_threshold", recordPointDistanceThreshold_))
492 {
493 }
494
495 if (!getNode()->get_parameter(
496 "record_angular_distance_threshold", recordAngularDistanceThreshold_))
497 {
498 }
499
500 if (!getNode()->get_parameter("clear_point_distance_threshold", clearPointDistanceThreshold_))
501 {
502 }
503
504 if (!getNode()->get_parameter("clear_angular_distance_threshold", clearAngularDistanceThreshold_))
505 {
506 }
507}
508
514void OdomTracker::processOdometryMessage(const nav_msgs::msg::Odometry::SharedPtr odom)
515{
516 RCLCPP_INFO_THROTTLE(getLogger(), *getNode()->get_clock(), 2000, "[odom_tracker] update");
517 std::lock_guard<std::mutex> lock(m_mutex_);
518
520
522 {
523 updateRecordPath(*odom);
524 }
526 {
527 updateClearPath(*odom);
528 }
529
530 // RCLCPP_WARN(getLogger(),"odomTracker odometry callback");
531 if (publishMessages)
532 {
533 rtPublishPaths(odom->header.stamp);
534 }
535
536 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
537}
538} // namespace odom_tracker
539} // 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)
void logStateString(bool debug=true)
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() const
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)