SMACC2
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 ()
 
- 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)
 
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 ()
 
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 234 of file odom_tracker.cpp.

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}
virtual void rtPublishPaths(rclcpp::Time timestamp)
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(), sm_dance_bot::radial_motion_states::StiRadialReturn::onExit(), and sm_dance_bot_strikes_back::radial_motion_states::StiRadialReturn::onExit().

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 292 of file odom_tracker.cpp.

293{
294 std::lock_guard<std::mutex> lock(m_mutex_);
295 return this->currentMotionGoal_;
296}

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 298 of file odom_tracker.cpp.

299{
300 std::lock_guard<std::mutex> lock(m_mutex_);
301 return this->baseTrajectory_;
302}

References baseTrajectory_, and m_mutex_.

◆ logStateString()

void cl_nav2z::odom_tracker::OdomTracker::logStateString ( )

Definition at line 204 of file odom_tracker.cpp.

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

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

Referenced by clearPath(), 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::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}
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 167 of file odom_tracker.cpp.

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}

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 497 of file odom_tracker.cpp.

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}
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, 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 142 of file odom_tracker.cpp.

142{ 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 144 of file odom_tracker.cpp.

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}

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 309 of file odom_tracker.cpp.

310{
311 baseTrajectory_.header.stamp = timestamp;
313
314 aggregatedStackPathMsg_.header.stamp = timestamp;
316}
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 286 of file odom_tracker.cpp.

287{
288 std::lock_guard<std::mutex> lock(m_mutex_);
289 this->currentMotionGoal_ = pose;
290}

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 246 of file odom_tracker.cpp.

247{
248 currentPathName_ = currentPathName;
249}

References currentPathName_.

◆ setPublishMessages()

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

setPublishMessages()

Definition at line 133 of file odom_tracker.cpp.

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}

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 266 of file odom_tracker.cpp.

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}

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 251 of file odom_tracker.cpp.

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}

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 95 of file odom_tracker.cpp.

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}

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::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 318 of file odom_tracker.cpp.

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}

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 335 of file odom_tracker.cpp.

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}
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 468 of file odom_tracker.cpp.

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}

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 414 of file odom_tracker.cpp.

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}

References baseTrajectory_, 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: