SMACC2
Loading...
Searching...
No Matches
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
cl_nav2z::odom_tracker::OdomTracker Class Reference

#include <odom_tracker.hpp>

Inheritance diagram for cl_nav2z::odom_tracker::OdomTracker:
Inheritance graph
Collaboration diagram for cl_nav2z::odom_tracker::OdomTracker:
Collaboration graph

Classes

struct  PathInfo
 

Public Member Functions

 OdomTracker (std::string odomtopicName="/odom", std::string odomFrame="odom")
 
virtual void processOdometryMessage (const nav_msgs::msg::Odometry::SharedPtr odom)
 odom callback: Updates the path - this must be called periodically for each odometry message. More...
 
void setWorkingMode (WorkingMode workingMode)
 
void setPublishMessages (bool value)
 
void pushPath ()
 
void pushPath (std::string pathname)
 
void popPath (int pathCount=1, bool keepPreviousPath=false)
 
void clearPath ()
 
void setStartPoint (const geometry_msgs::msg::PoseStamped &pose)
 
void setStartPoint (const geometry_msgs::msg::Pose &pose)
 
void setCurrentMotionGoal (const geometry_msgs::msg::PoseStamped &pose)
 
void setCurrentPathName (const std::string &currentPathName)
 
std::optional< geometry_msgs::msg::PoseStamped > getCurrentMotionGoal ()
 
nav_msgs::msg::Path getPath ()
 
void logStateString (bool debug=true)
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Protected Member Functions

void onInitialize () override
 
void updateConfiguration ()
 
virtual void rtPublishPaths (rclcpp::Time timestamp)
 
virtual bool updateRecordPath (const nav_msgs::msg::Odometry &odom)
 
virtual bool updateClearPath (const nav_msgs::msg::Odometry &odom)
 
void updateAggregatedStackPath ()
 
- Protected Member Functions inherited from smacc2::ISmaccComponent
virtual void onInitialize ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 

Protected Attributes

rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathPub_
 
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathStackedPub_
 
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odomSub_
 
double recordPointDistanceThreshold_
 How much distance there is between two points of the path. More...
 
double recordAngularDistanceThreshold_
 Meters. More...
 
double clearPointDistanceThreshold_
 rads More...
 
double clearAngularDistanceThreshold_
 rads More...
 
std::string odomFrame_
 
std::string odomTopicName_
 
bool publishMessages
 
nav_msgs::msg::Path baseTrajectory_
 Processed path for the mouth of the reel. More...
 
WorkingMode workingMode_
 
std::vector< nav_msgs::msg::Path > pathStack_
 
std::vector< PathInfopathInfos_
 
nav_msgs::msg::Path aggregatedStackPathMsg_
 
bool subscribeToOdometryTopic_
 
std::optional< geometry_msgs::msg::PoseStamped > currentMotionGoal_
 
std::string currentPathName_
 
std::mutex m_mutex_
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

This object tracks and saves the trajectories performed by the vehicle so that they can be used later to execute operations such as "undo motions"

Definition at line 53 of file odom_tracker.hpp.

Constructor & Destructor Documentation

◆ OdomTracker()

cl_nav2z::odom_tracker::OdomTracker::OdomTracker ( std::string  odomtopicName = "/odom",
std::string  odomFrame = "odom" 
)

Member Function Documentation

◆ clearPath()

void cl_nav2z::odom_tracker::OdomTracker::clearPath ( )

Definition at line 246 of file odom_tracker.cpp.

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}
virtual void rtPublishPaths(rclcpp::Time timestamp)
void logStateString(bool debug=true)
std::optional< geometry_msgs::msg::PoseStamped > currentMotionGoal_
nav_msgs::msg::Path baseTrajectory_
Processed path for the mouth of the reel.
rclcpp::Node::SharedPtr getNode()

References baseTrajectory_, currentMotionGoal_, smacc2::ISmaccComponent::getNode(), logStateString(), m_mutex_, rtPublishPaths(), and updateAggregatedStackPath().

Referenced by cl_nav2z::CbNavigateBackwards::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCurrentMotionGoal()

std::optional< geometry_msgs::msg::PoseStamped > cl_nav2z::odom_tracker::OdomTracker::getCurrentMotionGoal ( )

Definition at line 304 of file odom_tracker.cpp.

305{
306 std::lock_guard<std::mutex> lock(m_mutex_);
307 return this->currentMotionGoal_;
308}

References currentMotionGoal_, and m_mutex_.

Referenced by cl_nav2z::CbRetry< TCbRelativeMotion >::onEntry().

Here is the caller graph for this function:

◆ getPath()

nav_msgs::msg::Path cl_nav2z::odom_tracker::OdomTracker::getPath ( )

Definition at line 310 of file odom_tracker.cpp.

311{
312 std::lock_guard<std::mutex> lock(m_mutex_);
313 return this->baseTrajectory_;
314}

References baseTrajectory_, and m_mutex_.

Referenced by cl_nav2z::CbUndoPathBackwards::onEntry().

Here is the caller graph for this function:

◆ logStateString()

void cl_nav2z::odom_tracker::OdomTracker::logStateString ( bool  debug = true)

Definition at line 212 of file odom_tracker.cpp.

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}
std::vector< nav_msgs::msg::Path > pathStack_
std::vector< PathInfo > pathInfos_
rclcpp::Logger getLogger() const

References baseTrajectory_, currentPathName_, smacc2::ISmaccComponent::getLogger(), pathInfos_, and pathStack_.

Referenced by clearPath(), cl_nav2z::CbUndoPathBackwards::onEntry(), cl_nav2z::CbUndoPathBackwards::onExit(), popPath(), and pushPath().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

void cl_nav2z::odom_tracker::OdomTracker::onInitialize ( )
overrideprotectedvirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 56 of file odom_tracker.cpp.

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}
double recordPointDistanceThreshold_
How much distance there is between two points of the path.
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathPub_
virtual void processOdometryMessage(const nav_msgs::msg::Odometry::SharedPtr odom)
odom callback: Updates the path - this must be called periodically for each odometry message.
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odomSub_
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathStackedPub_
void parameterDeclareAndtryGetOrSet(rclcpp::Node::SharedPtr &node, std::string param_name, T &value)

References clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), odomFrame_, odomSub_, odomTopicName_, cl_nav2z::odom_tracker::parameterDeclareAndtryGetOrSet(), processOdometryMessage(), recordAngularDistanceThreshold_, recordPointDistanceThreshold_, robotBasePathPub_, robotBasePathStackedPub_, and subscribeToOdometryTopic_.

Here is the call graph for this function:

◆ popPath()

void cl_nav2z::odom_tracker::OdomTracker::popPath ( int  pathCount = 1,
bool  keepPreviousPath = false 
)

Definition at line 175 of file odom_tracker.cpp.

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}

References baseTrajectory_, currentMotionGoal_, smacc2::ISmaccComponent::getLogger(), logStateString(), m_mutex_, pathInfos_, pathStack_, and updateAggregatedStackPath().

Referenced by OdomTrackerActionServer::execute(), and cl_nav2z::CbUndoPathBackwards::onExit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processOdometryMessage()

void cl_nav2z::odom_tracker::OdomTracker::processOdometryMessage ( const nav_msgs::msg::Odometry::SharedPtr  odom)
virtual

odom callback: Updates the path - this must be called periodically for each odometry message.

processOdometryMessage()

Definition at line 514 of file odom_tracker.cpp.

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}
virtual bool updateClearPath(const nav_msgs::msg::Odometry &odom)
virtual bool updateRecordPath(const nav_msgs::msg::Odometry &odom)

References cl_nav2z::odom_tracker::CLEAR_PATH, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), m_mutex_, publishMessages, cl_nav2z::odom_tracker::RECORD_PATH, rtPublishPaths(), updateClearPath(), updateConfiguration(), updateRecordPath(), and workingMode_.

Referenced by onInitialize().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pushPath() [1/2]

void cl_nav2z::odom_tracker::OdomTracker::pushPath ( )

Definition at line 145 of file odom_tracker.cpp.

145{ this->pushPath(std::string()); }

References pushPath().

Referenced by OdomTrackerActionServer::execute(), cl_nav2z::CbNavigateForward::onEntry(), and pushPath().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pushPath() [2/2]

void cl_nav2z::odom_tracker::OdomTracker::pushPath ( std::string  pathname)

Definition at line 147 of file odom_tracker.cpp.

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}

References baseTrajectory_, currentMotionGoal_, currentPathName_, smacc2::ISmaccComponent::getLogger(), logStateString(), m_mutex_, pathInfos_, pathStack_, and updateAggregatedStackPath().

Here is the call graph for this function:

◆ rtPublishPaths()

void cl_nav2z::odom_tracker::OdomTracker::rtPublishPaths ( rclcpp::Time  timestamp)
protectedvirtual

rtPublishPaths()

Definition at line 321 of file odom_tracker.cpp.

322{
323 baseTrajectory_.header.stamp = timestamp;
325
326 aggregatedStackPathMsg_.header.stamp = timestamp;
328}
nav_msgs::msg::Path aggregatedStackPathMsg_

References aggregatedStackPathMsg_, baseTrajectory_, robotBasePathPub_, and robotBasePathStackedPub_.

Referenced by clearPath(), and processOdometryMessage().

Here is the caller graph for this function:

◆ setCurrentMotionGoal()

void cl_nav2z::odom_tracker::OdomTracker::setCurrentMotionGoal ( const geometry_msgs::msg::PoseStamped &  pose)

Definition at line 298 of file odom_tracker.cpp.

299{
300 std::lock_guard<std::mutex> lock(m_mutex_);
301 this->currentMotionGoal_ = pose;
302}

References currentMotionGoal_, and m_mutex_.

Referenced by cl_nav2z::CbNavigateForward::onEntry().

Here is the caller graph for this function:

◆ setCurrentPathName()

void cl_nav2z::odom_tracker::OdomTracker::setCurrentPathName ( const std::string &  currentPathName)

Definition at line 258 of file odom_tracker.cpp.

259{
260 currentPathName_ = currentPathName;
261}

References currentPathName_.

◆ setPublishMessages()

void cl_nav2z::odom_tracker::OdomTracker::setPublishMessages ( bool  value)

setPublishMessages()

Definition at line 136 of file odom_tracker.cpp.

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}

References m_mutex_, publishMessages, and updateAggregatedStackPath().

Referenced by OdomTrackerActionServer::execute().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setStartPoint() [1/2]

void cl_nav2z::odom_tracker::OdomTracker::setStartPoint ( const geometry_msgs::msg::Pose &  pose)

Definition at line 278 of file odom_tracker.cpp.

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}

References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), m_mutex_, odomFrame_, and updateAggregatedStackPath().

Here is the call graph for this function:

◆ setStartPoint() [2/2]

void cl_nav2z::odom_tracker::OdomTracker::setStartPoint ( const geometry_msgs::msg::PoseStamped &  pose)

Definition at line 263 of file odom_tracker.cpp.

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}

References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), m_mutex_, and updateAggregatedStackPath().

Referenced by cl_nav2z::CbNavigateBackwards::onEntry(), and cl_nav2z::CbNavigateForward::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setWorkingMode()

void cl_nav2z::odom_tracker::OdomTracker::setWorkingMode ( WorkingMode  workingMode)

setWorkingMode()

Definition at line 98 of file odom_tracker.cpp.

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}

References cl_nav2z::odom_tracker::CLEAR_PATH, clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getLogger(), cl_nav2z::odom_tracker::IDLE, m_mutex_, cl_nav2z::odom_tracker::RECORD_PATH, recordAngularDistanceThreshold_, recordPointDistanceThreshold_, and workingMode_.

Referenced by OdomTrackerActionServer::execute(), cl_nav2z::CbNavigateBackwards::onEntry(), cl_nav2z::CbNavigateForward::onEntry(), cl_nav2z::CbUndoPathBackwards::onEntry(), cl_nav2z::CbNavigateBackwards::onExit(), and cl_nav2z::CbNavigateForward::onExit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateAggregatedStackPath()

void cl_nav2z::odom_tracker::OdomTracker::updateAggregatedStackPath ( )
protected

Definition at line 330 of file odom_tracker.cpp.

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}

References aggregatedStackPathMsg_, odomFrame_, and pathStack_.

Referenced by clearPath(), popPath(), pushPath(), setPublishMessages(), and setStartPoint().

Here is the caller graph for this function:

◆ updateClearPath()

bool cl_nav2z::odom_tracker::OdomTracker::updateClearPath ( const nav_msgs::msg::Odometry &  odom)
protectedvirtual

updateBackward()

Track robot base pose

Not removing point because it is enough far from the last cord point

Definition at line 347 of file odom_tracker.cpp.

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}
double p2pDistance(const geometry_msgs::msg::Point &p1, const geometry_msgs::msg::Point &p2)

References baseTrajectory_, clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getLogger(), and cl_nav2z::odom_tracker::p2pDistance().

Referenced by processOdometryMessage().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateConfiguration()

void cl_nav2z::odom_tracker::OdomTracker::updateConfiguration ( )
protected

reconfigCB()

Definition at line 485 of file odom_tracker.cpp.

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}

References clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getNode(), odomFrame_, recordAngularDistanceThreshold_, and recordPointDistanceThreshold_.

Referenced by processOdometryMessage().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateRecordPath()

bool cl_nav2z::odom_tracker::OdomTracker::updateRecordPath ( const nav_msgs::msg::Odometry &  odom)
protectedvirtual

updateRecordPath()

Track robot base pose

Definition at line 426 of file odom_tracker.cpp.

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}

References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), cl_nav2z::odom_tracker::p2pDistance(), recordAngularDistanceThreshold_, and recordPointDistanceThreshold_.

Referenced by processOdometryMessage().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ aggregatedStackPathMsg_

nav_msgs::msg::Path cl_nav2z::odom_tracker::OdomTracker::aggregatedStackPathMsg_
protected

Definition at line 163 of file odom_tracker.hpp.

Referenced by rtPublishPaths(), and updateAggregatedStackPath().

◆ baseTrajectory_

nav_msgs::msg::Path cl_nav2z::odom_tracker::OdomTracker::baseTrajectory_
protected

Processed path for the mouth of the reel.

Definition at line 149 of file odom_tracker.hpp.

Referenced by clearPath(), getPath(), logStateString(), popPath(), pushPath(), rtPublishPaths(), setStartPoint(), updateClearPath(), and updateRecordPath().

◆ clearAngularDistanceThreshold_

double cl_nav2z::odom_tracker::OdomTracker::clearAngularDistanceThreshold_
protected

rads

Definition at line 138 of file odom_tracker.hpp.

Referenced by onInitialize(), setWorkingMode(), updateClearPath(), and updateConfiguration().

◆ clearPointDistanceThreshold_

double cl_nav2z::odom_tracker::OdomTracker::clearPointDistanceThreshold_
protected

rads

Definition at line 135 of file odom_tracker.hpp.

Referenced by onInitialize(), setWorkingMode(), updateClearPath(), and updateConfiguration().

◆ currentMotionGoal_

std::optional<geometry_msgs::msg::PoseStamped> cl_nav2z::odom_tracker::OdomTracker::currentMotionGoal_
protected

◆ currentPathName_

std::string cl_nav2z::odom_tracker::OdomTracker::currentPathName_
protected

Definition at line 169 of file odom_tracker.hpp.

Referenced by logStateString(), pushPath(), and setCurrentPathName().

◆ m_mutex_

std::mutex cl_nav2z::odom_tracker::OdomTracker::m_mutex_
protected

◆ odomFrame_

std::string cl_nav2z::odom_tracker::OdomTracker::odomFrame_
protected

◆ odomSub_

rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr cl_nav2z::odom_tracker::OdomTracker::odomSub_
protected

Definition at line 125 of file odom_tracker.hpp.

Referenced by onInitialize().

◆ odomTopicName_

std::string cl_nav2z::odom_tracker::OdomTracker::odomTopicName_
protected

Definition at line 142 of file odom_tracker.hpp.

Referenced by OdomTracker(), and onInitialize().

◆ pathInfos_

std::vector<PathInfo> cl_nav2z::odom_tracker::OdomTracker::pathInfos_
protected

Definition at line 161 of file odom_tracker.hpp.

Referenced by logStateString(), popPath(), and pushPath().

◆ pathStack_

std::vector<nav_msgs::msg::Path> cl_nav2z::odom_tracker::OdomTracker::pathStack_
protected

Definition at line 153 of file odom_tracker.hpp.

Referenced by logStateString(), popPath(), pushPath(), and updateAggregatedStackPath().

◆ publishMessages

bool cl_nav2z::odom_tracker::OdomTracker::publishMessages
protected

Definition at line 146 of file odom_tracker.hpp.

Referenced by OdomTracker(), processOdometryMessage(), and setPublishMessages().

◆ recordAngularDistanceThreshold_

double cl_nav2z::odom_tracker::OdomTracker::recordAngularDistanceThreshold_
protected

Meters.

Definition at line 132 of file odom_tracker.hpp.

Referenced by onInitialize(), setWorkingMode(), updateConfiguration(), and updateRecordPath().

◆ recordPointDistanceThreshold_

double cl_nav2z::odom_tracker::OdomTracker::recordPointDistanceThreshold_
protected

How much distance there is between two points of the path.

Definition at line 129 of file odom_tracker.hpp.

Referenced by onInitialize(), setWorkingMode(), updateConfiguration(), and updateRecordPath().

◆ robotBasePathPub_

rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr cl_nav2z::odom_tracker::OdomTracker::robotBasePathPub_
protected

Definition at line 119 of file odom_tracker.hpp.

Referenced by onInitialize(), and rtPublishPaths().

◆ robotBasePathStackedPub_

rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr cl_nav2z::odom_tracker::OdomTracker::robotBasePathStackedPub_
protected

Definition at line 120 of file odom_tracker.hpp.

Referenced by onInitialize(), and rtPublishPaths().

◆ subscribeToOdometryTopic_

bool cl_nav2z::odom_tracker::OdomTracker::subscribeToOdometryTopic_
protected

Definition at line 166 of file odom_tracker.hpp.

Referenced by OdomTracker(), and onInitialize().

◆ workingMode_

WorkingMode cl_nav2z::odom_tracker::OdomTracker::workingMode_
protected

Definition at line 151 of file odom_tracker.hpp.

Referenced by OdomTracker(), processOdometryMessage(), and setWorkingMode().


The documentation for this class was generated from the following files: