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

This class track the required distance of the cord based on the external localization system. More...

#include <odom_tracker.h>

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

Public Member Functions

 OdomTracker (std::string odomtopicName="/odom", std::string odomFrame="odom")
 
virtual void processOdometryMessage (const nav_msgs::Odometry &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 (std::string newPathTagName="")
 
void popPath (int pathCount=1, bool keepPreviousPath=false)
 
void clearPath ()
 
void setStartPoint (const geometry_msgs::PoseStamped &pose)
 
void setStartPoint (const geometry_msgs::Pose &pose)
 
nav_msgs::Path getPath ()
 
void logStateString ()
 
const std::vector< StackedPathEntrygetStackedPaths () const
 
- Public Member Functions inherited from smacc::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Protected Member Functions

void reconfigCB (move_base_z_client_plugin::OdomTrackerConfig &config, uint32_t level)
 
virtual void rtPublishPaths (ros::Time timestamp)
 
virtual bool updateRecordPath (const nav_msgs::Odometry &odom)
 
virtual bool updateClearPath (const nav_msgs::Odometry &odom)
 
void updateAggregatedStackPath ()
 
- Protected Member Functions inherited from smacc::ISmaccComponent
virtual void initialize (ISmaccClient *owner)
 
void setStateMachine (ISmaccStateMachine *stateMachine)
 
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)
 
virtual void onInitialize ()
 
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)
 

Protected Attributes

dynamic_reconfigure::Server< move_base_z_client_plugin::OdomTrackerConfig > paramServer_
 
dynamic_reconfigure::Server< move_base_z_client_plugin::OdomTrackerConfig >::CallbackType f
 
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Path > > robotBasePathPub_
 
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Path > > robotBasePathStackedPub_
 
ros::Subscriber 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_
 
bool publishMessages
 
nav_msgs::Path baseTrajectory_
 Processed path for the mouth of the reel. More...
 
WorkingMode workingMode_
 
std::vector< StackedPathEntrypathStack_
 
nav_msgs::Path aggregatedStackPathMsg_
 
bool subscribeToOdometryTopic_
 
std::string currentPathTagName_ ="Initial State"
 
std::mutex m_mutex_
 
- Protected Attributes inherited from smacc::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

This class track the required distance of the cord based on the external localization system.

Definition at line 46 of file odom_tracker.h.

Constructor & Destructor Documentation

◆ OdomTracker()

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

Definition at line 14 of file odom_tracker.cpp.

15 : paramServer_(ros::NodeHandle("~/odom_tracker"))
16{
18 publishMessages = true;
20 this->odomFrame_ = odomFrame;
21
22 ros::NodeHandle nh("~/odom_tracker");
23
24 ROS_WARN("Initializing Odometry Tracker");
25
26 if (!nh.getParam("odom_frame", this->odomFrame_))
27 {
28 ROS_INFO_STREAM("[OdomTracker] odomFrame:" << this->odomFrame_);
29 }
30 ROS_INFO_STREAM("[OdomTracker] odomFrame overwritten by ros parameter:" << this->odomFrame_);
31
32 if (!nh.getParam("record_point_distance_threshold", recordPointDistanceThreshold_))
33 {
34 recordPointDistanceThreshold_ = 0.005; // 5 mm
35 }
36 ROS_INFO_STREAM("[OdomTracker] record_point_distance_threshold :" << recordPointDistanceThreshold_);
37
38 if (!nh.getParam("record_angular_distance_threshold", recordAngularDistanceThreshold_))
39 {
40 recordAngularDistanceThreshold_ = 0.1; // radians
41 }
42 ROS_INFO_STREAM("[OdomTracker] record_angular_distance_threshold :" << recordAngularDistanceThreshold_);
43
44 if (!nh.getParam("clear_point_distance_threshold", clearPointDistanceThreshold_))
45 {
46 clearPointDistanceThreshold_ = 0.05; // 5 cm
47 }
48 ROS_INFO_STREAM("[OdomTracker] clear_point_distance_threshold :" << clearPointDistanceThreshold_);
49
50 if (!nh.getParam("clear_angular_distance_threshold", clearAngularDistanceThreshold_))
51 {
52 clearAngularDistanceThreshold_ = 0.1; // radians
53 }
54 ROS_INFO_STREAM("[OdomTracker] clear_angular_distance_threshold :" << clearAngularDistanceThreshold_);
55
57 {
58 odomSub_ = nh.subscribe(odomTopicName, 1, &OdomTracker::processOdometryMessage, this);
59 }
60
61 robotBasePathPub_ = std::make_shared<realtime_tools::RealtimePublisher<nav_msgs::Path>>(nh, "odom_tracker_path", 1);
63 std::make_shared<realtime_tools::RealtimePublisher<nav_msgs::Path>>(nh, "odom_tracker_stacked_path", 1);
64
65 f = boost::bind(&OdomTracker::reconfigCB, this, _1, _2);
66 paramServer_.setCallback(f);
67}
virtual void processOdometryMessage(const nav_msgs::Odometry &odom)
odom callback: Updates the path - this must be called periodically for each odometry message.
dynamic_reconfigure::Server< move_base_z_client_plugin::OdomTrackerConfig >::CallbackType f
Definition: odom_tracker.h:92
double recordPointDistanceThreshold_
How much distance there is between two points of the path.
Definition: odom_tracker.h:118
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Path > > robotBasePathPub_
Definition: odom_tracker.h:108
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Path > > robotBasePathStackedPub_
Definition: odom_tracker.h:109
dynamic_reconfigure::Server< move_base_z_client_plugin::OdomTrackerConfig > paramServer_
Definition: odom_tracker.h:91
void reconfigCB(move_base_z_client_plugin::OdomTrackerConfig &config, uint32_t level)

References clearAngularDistanceThreshold_, clearPointDistanceThreshold_, f, odomFrame_, odomSub_, paramServer_, processOdometryMessage(), publishMessages, reconfigCB(), cl_move_base_z::odom_tracker::RECORD_PATH, recordAngularDistanceThreshold_, recordPointDistanceThreshold_, robotBasePathPub_, robotBasePathStackedPub_, subscribeToOdometryTopic_, and workingMode_.

Here is the call graph for this function:

Member Function Documentation

◆ clearPath()

void cl_move_base_z::odom_tracker::OdomTracker::clearPath ( )

Definition at line 166 of file odom_tracker.cpp.

167{
168 std::lock_guard<std::mutex> lock(m_mutex_);
169 baseTrajectory_.poses.clear();
170
171 rtPublishPaths(ros::Time::now());
172 this->logStateString();
174}
nav_msgs::Path baseTrajectory_
Processed path for the mouth of the reel.
Definition: odom_tracker.h:136
virtual void rtPublishPaths(ros::Time timestamp)

References baseTrajectory_, logStateString(), m_mutex_, rtPublishPaths(), and updateAggregatedStackPath().

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

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

◆ getPath()

nav_msgs::Path cl_move_base_z::odom_tracker::OdomTracker::getPath ( )

Definition at line 211 of file odom_tracker.cpp.

212{
213 std::lock_guard<std::mutex> lock(m_mutex_);
214 return this->baseTrajectory_;
215}

References baseTrajectory_, and m_mutex_.

Referenced by cl_move_base_z::CbUndoPathBackwards2::onEntry().

Here is the caller graph for this function:

◆ getStackedPaths()

const std::vector< StackedPathEntry > cl_move_base_z::odom_tracker::OdomTracker::getStackedPaths ( ) const
inline

Definition at line 85 of file odom_tracker.h.

86 {
87 return this->pathStack_;
88 }
std::vector< StackedPathEntry > pathStack_
Definition: odom_tracker.h:140

References pathStack_.

◆ logStateString()

void cl_move_base_z::odom_tracker::OdomTracker::logStateString ( )

Definition at line 152 of file odom_tracker.cpp.

153{
154 ROS_INFO("--- odom tracker state ---");
155 ROS_INFO(" - stacked paths count: %ld", pathStack_.size());
156 ROS_INFO_STREAM(" - [STACK-HEAD active path '" << currentPathTagName_ <<"' size: "<< baseTrajectory_.poses.size()<<"]");
157 int i = 0;
158 for (auto &p : pathStack_ | boost::adaptors::reversed)
159 {
160 ROS_INFO_STREAM(" - p " << i << "[" << p.path.header.stamp << "][" << p.pathTagName << "], size: " << p.path.poses.size());
161 i++;
162 }
163 ROS_INFO("---");
164}

References baseTrajectory_, currentPathTagName_, and pathStack_.

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

Here is the caller graph for this function:

◆ popPath()

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

Definition at line 122 of file odom_tracker.cpp.

123{
124 ROS_INFO("odom_tracker m_mutex acquire");
125 std::lock_guard<std::mutex> lock(m_mutex_);
126
127 ROS_INFO("POP PATH ENTRY");
128 this->logStateString();
129
130 if (!keepPreviousPath)
131 {
132 baseTrajectory_.poses.clear();
133 }
134
135 while (popCount > 0 && !pathStack_.empty())
136 {
137 auto &stacked = pathStack_.back().path.poses;
138 baseTrajectory_.poses.insert(baseTrajectory_.poses.begin(), stacked.begin(), stacked.end());
139 pathStack_.pop_back();
140 popCount--;
141
142 ROS_INFO("POP PATH Iteration ");
143 this->logStateString();
144 }
145
146 ROS_INFO("POP PATH EXITING");
147 this->logStateString();
148 ROS_INFO("odom_tracker m_mutex release");
150}

References baseTrajectory_, logStateString(), m_mutex_, pathStack_, and updateAggregatedStackPath().

Referenced by OdomTrackerActionServer::execute().

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

◆ processOdometryMessage()

void cl_move_base_z::odom_tracker::OdomTracker::processOdometryMessage ( const nav_msgs::Odometry &  odom)
virtual

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

processOdometryMessage()

Definition at line 403 of file odom_tracker.cpp.

404{
405 // ROS_INFO("odom_tracker m_mutex acquire");
406 std::lock_guard<std::mutex> lock(m_mutex_);
407
409 {
410 updateRecordPath(odom);
411 }
413 {
414 updateClearPath(odom);
415 }
416
417 // ROS_WARN("odomTracker odometry callback");
418 if (publishMessages)
419 {
420 rtPublishPaths(odom.header.stamp);
421 }
422
423 // ROS_INFO("odom_tracker m_mutex release");
424}
virtual bool updateRecordPath(const nav_msgs::Odometry &odom)
virtual bool updateClearPath(const nav_msgs::Odometry &odom)

References cl_move_base_z::odom_tracker::CLEAR_PATH, m_mutex_, publishMessages, cl_move_base_z::odom_tracker::RECORD_PATH, rtPublishPaths(), updateClearPath(), updateRecordPath(), and workingMode_.

Referenced by OdomTracker().

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

◆ pushPath()

void cl_move_base_z::odom_tracker::OdomTracker::pushPath ( std::string  newPathTagName = "")

Definition at line 97 of file odom_tracker.cpp.

98{
99 ROS_INFO("odom_tracker m_mutex acquire");
100 std::lock_guard<std::mutex> lock(m_mutex_);
101 ROS_INFO("PUSH_PATH PATH EXITING");
102 this->logStateString();
103
105 baseTrajectory_.poses.clear();
106
107 if(newPathTagName =="")
108 {
109 this->currentPathTagName_="(unspecified path name)";
110 }
111 else
112 {
113 this->currentPathTagName_ = newPathTagName;
114 }
115
116 ROS_INFO("PUSH_PATH PATH EXITING");
117 this->logStateString();
118 ROS_INFO("odom_tracker m_mutex release");
120}

References baseTrajectory_, currentPathTagName_, logStateString(), m_mutex_, pathStack_, and updateAggregatedStackPath().

Referenced by OdomTrackerActionServer::execute(), cl_move_base_z::CbAbsoluteRotate::onEntry(), and cl_move_base_z::CbNavigateForward::onEntry().

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

◆ reconfigCB()

void cl_move_base_z::odom_tracker::OdomTracker::reconfigCB ( move_base_z_client_plugin::OdomTrackerConfig &  config,
uint32_t  level 
)
protected

reconfigCB()

Definition at line 387 of file odom_tracker.cpp.

388{
389 ROS_INFO("[OdomTracker] reconfigure Request");
390 this->odomFrame_ = config.odom_frame;
391
392 this->recordPointDistanceThreshold_ = config.record_point_distance_threshold;
393 this->recordAngularDistanceThreshold_ = config.record_angular_distance_threshold;
394 this->clearPointDistanceThreshold_ = config.clear_point_distance_threshold;
395 this->clearAngularDistanceThreshold_ = config.clear_angular_distance_threshold;
396}

References clearAngularDistanceThreshold_, clearPointDistanceThreshold_, odomFrame_, recordAngularDistanceThreshold_, and recordPointDistanceThreshold_.

Referenced by OdomTracker().

Here is the caller graph for this function:

◆ rtPublishPaths()

void cl_move_base_z::odom_tracker::OdomTracker::rtPublishPaths ( ros::Time  timestamp)
protectedvirtual

rtPublishPaths()

Copy trajectory

Copy trajectory

Definition at line 222 of file odom_tracker.cpp.

223{
224 if (robotBasePathPub_->trylock())
225 {
226 nav_msgs::Path &msg = robotBasePathPub_->msg_;
228
229 msg = baseTrajectory_;
230
231 msg.header.stamp = timestamp;
232 robotBasePathPub_->unlockAndPublish();
233 }
234
235 if (robotBasePathStackedPub_->trylock())
236 {
237 nav_msgs::Path &msg = robotBasePathStackedPub_->msg_;
239
241 msg.header.stamp = timestamp;
242 robotBasePathStackedPub_->unlockAndPublish();
243 }
244}

References aggregatedStackPathMsg_, baseTrajectory_, robotBasePathPub_, and robotBasePathStackedPub_.

Referenced by clearPath(), and processOdometryMessage().

Here is the caller graph for this function:

◆ setPublishMessages()

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

setPublishMessages()

Definition at line 88 of file odom_tracker.cpp.

89{
90 // ROS_INFO("odom_tracker m_mutex acquire");
91 std::lock_guard<std::mutex> lock(m_mutex_);
92 publishMessages = value;
93 // ROS_INFO("odom_tracker m_mutex release");
95}

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_move_base_z::odom_tracker::OdomTracker::setStartPoint ( const geometry_msgs::Pose &  pose)

Definition at line 191 of file odom_tracker.cpp.

192{
193 std::lock_guard<std::mutex> lock(m_mutex_);
194 ROS_INFO_STREAM("[OdomTracker] set current path starting point: " << pose);
195 geometry_msgs::PoseStamped posestamped;
196 posestamped.header.frame_id = this->odomFrame_;
197 posestamped.header.stamp = ros::Time::now();
198 posestamped.pose = pose;
199
200 if (baseTrajectory_.poses.size() > 0)
201 {
202 baseTrajectory_.poses[0] = posestamped;
203 }
204 else
205 {
206 baseTrajectory_.poses.push_back(posestamped);
207 }
209}

References baseTrajectory_, m_mutex_, odomFrame_, and updateAggregatedStackPath().

Here is the call graph for this function:

◆ setStartPoint() [2/2]

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

Definition at line 176 of file odom_tracker.cpp.

177{
178 std::lock_guard<std::mutex> lock(m_mutex_);
179 ROS_INFO_STREAM("[OdomTracker] set current path starting point: " << pose);
180 if (baseTrajectory_.poses.size() > 0)
181 {
182 baseTrajectory_.poses[0] = pose;
183 }
184 else
185 {
186 baseTrajectory_.poses.push_back(pose);
187 }
189}

References baseTrajectory_, m_mutex_, and updateAggregatedStackPath().

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

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

◆ setWorkingMode()

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

setWorkingMode()

Definition at line 74 of file odom_tracker.cpp.

75{
76 // ROS_INFO("odom_tracker m_mutex acquire");
77 std::lock_guard<std::mutex> lock(m_mutex_);
78 ROS_INFO("[OdomTracker] setting working mode to: %d", (uint8_t)workingMode);
79 workingMode_ = workingMode;
80 // ROS_INFO("odom_tracker m_mutex release");
81}

References m_mutex_, and workingMode_.

Referenced by OdomTrackerActionServer::execute(), cl_move_base_z::CbNavigateBackwards::onEntry(), cl_move_base_z::CbNavigateForward::onEntry(), cl_move_base_z::CbUndoPathBackwards2::onEntry(), cl_move_base_z::CbNavigateBackwards::onExit(), and cl_move_base_z::CbNavigateForward::onExit().

Here is the caller graph for this function:

◆ updateAggregatedStackPath()

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

Definition at line 246 of file odom_tracker.cpp.

247{
248 aggregatedStackPathMsg_.poses.clear();
249 for (auto &p : pathStack_)
250 {
251 aggregatedStackPathMsg_.poses.insert(aggregatedStackPathMsg_.poses.end(), p.path.poses.begin(), p.path.poses.end());
252 }
253
254 aggregatedStackPathMsg_.header.frame_id = this->odomFrame_;
255}

References aggregatedStackPathMsg_, odomFrame_, and pathStack_.

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

Here is the caller graph for this function:

◆ updateClearPath()

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

updateBackward()

Track robot base pose

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

Definition at line 262 of file odom_tracker.cpp.

263{
264 // we initially accept any message if the queue is empty
266 geometry_msgs::PoseStamped base_pose;
267
268 base_pose.pose = odom.pose.pose;
269 base_pose.header = odom.header;
270 baseTrajectory_.header = odom.header;
271
272 bool acceptBackward = false;
273 bool clearingError = false;
274 bool finished = false;
275
276 while (!finished)
277 {
278 if (baseTrajectory_.poses.size() <= 1) // we at least keep always the first point of the forward path when clearing
279 // (this is important for backwards planner replanning and not losing the
280 // last goal)
281 {
282 acceptBackward = false;
283 finished = true;
284 }
285 else
286 {
287 auto &carrotPose = baseTrajectory_.poses.back().pose;
288 const geometry_msgs::Point &carrotPoint = carrotPose.position;
289 double carrotAngle = tf::getYaw(carrotPose.orientation);
290
291 auto &currePose = base_pose.pose;
292 const geometry_msgs::Point &currePoint = currePose.position;
293 double currentAngle = tf::getYaw(currePose.orientation);
294
295 double lastpointdist = p2pDistance(carrotPoint, currePoint);
296 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
297
298 acceptBackward = !baseTrajectory_.poses.empty() && lastpointdist < clearPointDistanceThreshold_ &&
299 goalAngleOffset < clearAngularDistanceThreshold_;
300
301 clearingError = lastpointdist > 2 * clearPointDistanceThreshold_;
302 ROS_DEBUG_STREAM("[OdomTracker] clearing (accepted: " << acceptBackward << ") linerr: " << lastpointdist
303 << ", anglerr: " << goalAngleOffset);
304 }
305
306 // ROS_INFO("Backwards, last distance: %lf < %lf accept: %d", dist, minPointDistanceBackwardThresh_,
307 // acceptBackward);
308 if (acceptBackward && baseTrajectory_.poses.size() > 1) /*we always leave at least one item, specially interesting
309 for the backward local planner reach the backwards goal
310 with precision enough*/
311 {
312 baseTrajectory_.poses.pop_back();
313 }
314 else if (clearingError)
315 {
316 finished = true;
317 ROS_WARN("[OdomTracker] Incorrect odom clearing motion.");
318 }
319 else
320 {
321 finished = true;
323 }
324 }
325
326 return acceptBackward;
327}
double p2pDistance(const geometry_msgs::Point &p1, const geometry_msgs::Point &p2)
Definition: odom_tracker.h:158

References baseTrajectory_, clearAngularDistanceThreshold_, clearPointDistanceThreshold_, and cl_move_base_z::odom_tracker::p2pDistance().

Referenced by processOdometryMessage().

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

◆ updateRecordPath()

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

updateRecordPath()

Track robot base pose

Definition at line 333 of file odom_tracker.cpp.

334{
336 geometry_msgs::PoseStamped base_pose;
337
338 base_pose.pose = odom.pose.pose;
339 base_pose.header = odom.header;
340 baseTrajectory_.header = odom.header;
341
342 bool enqueueOdomMessage = false;
343
344 double dist = -1;
345 if (baseTrajectory_.poses.empty())
346 {
347 enqueueOdomMessage = true;
348 }
349 else
350 {
351 const auto &prevPose = baseTrajectory_.poses.back().pose;
352 const geometry_msgs::Point &prevPoint = prevPose.position;
353 double prevAngle = tf::getYaw(prevPose.orientation);
354
355 const geometry_msgs::Point &currePoint = base_pose.pose.position;
356 double currentAngle = tf::getYaw(base_pose.pose.orientation);
357
358 dist = p2pDistance(prevPoint, currePoint);
359 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
360
361 // ROS_WARN("dist %lf vs min %lf", dist, recordPointDistanceThreshold_);
362
364 {
365 enqueueOdomMessage = true;
366 }
367 else
368 {
369 // ROS_WARN("skip odom, dist: %lf", dist);
370 enqueueOdomMessage = false;
371 }
372 }
373
374 if (enqueueOdomMessage)
375 {
376 baseTrajectory_.poses.push_back(base_pose);
377 }
378
379 return enqueueOdomMessage;
380}

References baseTrajectory_, cl_move_base_z::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::Path cl_move_base_z::odom_tracker::OdomTracker::aggregatedStackPathMsg_
protected

Definition at line 142 of file odom_tracker.h.

Referenced by rtPublishPaths(), and updateAggregatedStackPath().

◆ baseTrajectory_

nav_msgs::Path cl_move_base_z::odom_tracker::OdomTracker::baseTrajectory_
protected

Processed path for the mouth of the reel.

Definition at line 136 of file odom_tracker.h.

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

◆ clearAngularDistanceThreshold_

double cl_move_base_z::odom_tracker::OdomTracker::clearAngularDistanceThreshold_
protected

rads

Definition at line 127 of file odom_tracker.h.

Referenced by OdomTracker(), reconfigCB(), and updateClearPath().

◆ clearPointDistanceThreshold_

double cl_move_base_z::odom_tracker::OdomTracker::clearPointDistanceThreshold_
protected

rads

Definition at line 124 of file odom_tracker.h.

Referenced by OdomTracker(), reconfigCB(), and updateClearPath().

◆ currentPathTagName_

std::string cl_move_base_z::odom_tracker::OdomTracker::currentPathTagName_ ="Initial State"
protected

Definition at line 147 of file odom_tracker.h.

Referenced by logStateString(), and pushPath().

◆ f

dynamic_reconfigure::Server<move_base_z_client_plugin::OdomTrackerConfig>::CallbackType cl_move_base_z::odom_tracker::OdomTracker::f
protected

Definition at line 92 of file odom_tracker.h.

Referenced by OdomTracker().

◆ m_mutex_

std::mutex cl_move_base_z::odom_tracker::OdomTracker::m_mutex_
protected

◆ odomFrame_

std::string cl_move_base_z::odom_tracker::OdomTracker::odomFrame_
protected

Definition at line 129 of file odom_tracker.h.

Referenced by OdomTracker(), reconfigCB(), setStartPoint(), and updateAggregatedStackPath().

◆ odomSub_

ros::Subscriber cl_move_base_z::odom_tracker::OdomTracker::odomSub_
protected

Definition at line 114 of file odom_tracker.h.

Referenced by OdomTracker().

◆ paramServer_

dynamic_reconfigure::Server<move_base_z_client_plugin::OdomTrackerConfig> cl_move_base_z::odom_tracker::OdomTracker::paramServer_
protected

Definition at line 91 of file odom_tracker.h.

Referenced by OdomTracker().

◆ pathStack_

std::vector<StackedPathEntry> cl_move_base_z::odom_tracker::OdomTracker::pathStack_
protected

◆ publishMessages

bool cl_move_base_z::odom_tracker::OdomTracker::publishMessages
protected

Definition at line 133 of file odom_tracker.h.

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

◆ recordAngularDistanceThreshold_

double cl_move_base_z::odom_tracker::OdomTracker::recordAngularDistanceThreshold_
protected

Meters.

Definition at line 121 of file odom_tracker.h.

Referenced by OdomTracker(), reconfigCB(), and updateRecordPath().

◆ recordPointDistanceThreshold_

double cl_move_base_z::odom_tracker::OdomTracker::recordPointDistanceThreshold_
protected

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

Definition at line 118 of file odom_tracker.h.

Referenced by OdomTracker(), reconfigCB(), and updateRecordPath().

◆ robotBasePathPub_

std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Path> > cl_move_base_z::odom_tracker::OdomTracker::robotBasePathPub_
protected

Definition at line 108 of file odom_tracker.h.

Referenced by OdomTracker(), and rtPublishPaths().

◆ robotBasePathStackedPub_

std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Path> > cl_move_base_z::odom_tracker::OdomTracker::robotBasePathStackedPub_
protected

Definition at line 109 of file odom_tracker.h.

Referenced by OdomTracker(), and rtPublishPaths().

◆ subscribeToOdometryTopic_

bool cl_move_base_z::odom_tracker::OdomTracker::subscribeToOdometryTopic_
protected

Definition at line 145 of file odom_tracker.h.

Referenced by OdomTracker().

◆ workingMode_

WorkingMode cl_move_base_z::odom_tracker::OdomTracker::workingMode_
protected

Definition at line 138 of file odom_tracker.h.

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


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