SMACC2
|
#include <odom_tracker.hpp>
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 ¤tPathName) |
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 |
ISmaccStateMachine * | getStateMachine () |
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< PathInfo > | pathInfos_ |
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 | |
ISmaccStateMachine * | stateMachine_ |
ISmaccClient * | owner_ |
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.
cl_nav2z::odom_tracker::OdomTracker::OdomTracker | ( | std::string | odomtopicName = "/odom" , |
std::string | odomFrame = "odom" |
||
) |
Definition at line 32 of file odom_tracker.cpp.
References odomFrame_, odomTopicName_, publishMessages, cl_nav2z::odom_tracker::RECORD_PATH, subscribeToOdometryTopic_, and workingMode_.
void cl_nav2z::odom_tracker::OdomTracker::clearPath | ( | ) |
Definition at line 246 of file odom_tracker.cpp.
References baseTrajectory_, currentMotionGoal_, smacc2::ISmaccComponent::getNode(), logStateString(), m_mutex_, rtPublishPaths(), and updateAggregatedStackPath().
Referenced by cl_nav2z::CbNavigateBackwards::onEntry().
std::optional< geometry_msgs::msg::PoseStamped > cl_nav2z::odom_tracker::OdomTracker::getCurrentMotionGoal | ( | ) |
Definition at line 304 of file odom_tracker.cpp.
References currentMotionGoal_, and m_mutex_.
Referenced by cl_nav2z::CbRetry< TCbRelativeMotion >::onEntry().
nav_msgs::msg::Path cl_nav2z::odom_tracker::OdomTracker::getPath | ( | ) |
Definition at line 310 of file odom_tracker.cpp.
References baseTrajectory_, and m_mutex_.
Referenced by cl_nav2z::CbUndoPathBackwards::onEntry().
void cl_nav2z::odom_tracker::OdomTracker::logStateString | ( | bool | debug = true | ) |
Definition at line 212 of file odom_tracker.cpp.
References baseTrajectory_, currentPathName_, smacc2::ISmaccComponent::getLogger(), pathInfos_, and pathStack_.
Referenced by clearPath(), cl_nav2z::CbUndoPathBackwards::onEntry(), cl_nav2z::CbUndoPathBackwards::onExit(), popPath(), and pushPath().
|
overrideprotectedvirtual |
Reimplemented from smacc2::ISmaccComponent.
Definition at line 56 of file odom_tracker.cpp.
References clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), odomFrame_, odomSub_, odomTopicName_, cl_nav2z::odom_tracker::parameterDeclareAndtryGetOrSet(), processOdometryMessage(), recordAngularDistanceThreshold_, recordPointDistanceThreshold_, robotBasePathPub_, robotBasePathStackedPub_, and subscribeToOdometryTopic_.
void cl_nav2z::odom_tracker::OdomTracker::popPath | ( | int | pathCount = 1 , |
bool | keepPreviousPath = false |
||
) |
Definition at line 175 of file odom_tracker.cpp.
References baseTrajectory_, currentMotionGoal_, smacc2::ISmaccComponent::getLogger(), logStateString(), m_mutex_, pathInfos_, pathStack_, and updateAggregatedStackPath().
Referenced by OdomTrackerActionServer::execute(), and cl_nav2z::CbUndoPathBackwards::onExit().
|
virtual |
odom callback: Updates the path - this must be called periodically for each odometry message.
Definition at line 514 of file odom_tracker.cpp.
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().
void cl_nav2z::odom_tracker::OdomTracker::pushPath | ( | ) |
Definition at line 145 of file odom_tracker.cpp.
References pushPath().
Referenced by OdomTrackerActionServer::execute(), cl_nav2z::CbNavigateForward::onEntry(), and pushPath().
void cl_nav2z::odom_tracker::OdomTracker::pushPath | ( | std::string | pathname | ) |
Definition at line 147 of file odom_tracker.cpp.
References baseTrajectory_, currentMotionGoal_, currentPathName_, smacc2::ISmaccComponent::getLogger(), logStateString(), m_mutex_, pathInfos_, pathStack_, and updateAggregatedStackPath().
|
protectedvirtual |
Definition at line 321 of file odom_tracker.cpp.
References aggregatedStackPathMsg_, baseTrajectory_, robotBasePathPub_, and robotBasePathStackedPub_.
Referenced by clearPath(), and processOdometryMessage().
void cl_nav2z::odom_tracker::OdomTracker::setCurrentMotionGoal | ( | const geometry_msgs::msg::PoseStamped & | pose | ) |
Definition at line 298 of file odom_tracker.cpp.
References currentMotionGoal_, and m_mutex_.
Referenced by cl_nav2z::CbNavigateForward::onEntry().
void cl_nav2z::odom_tracker::OdomTracker::setCurrentPathName | ( | const std::string & | currentPathName | ) |
Definition at line 258 of file odom_tracker.cpp.
References currentPathName_.
void cl_nav2z::odom_tracker::OdomTracker::setPublishMessages | ( | bool | value | ) |
Definition at line 136 of file odom_tracker.cpp.
References m_mutex_, publishMessages, and updateAggregatedStackPath().
Referenced by OdomTrackerActionServer::execute().
void cl_nav2z::odom_tracker::OdomTracker::setStartPoint | ( | const geometry_msgs::msg::Pose & | pose | ) |
Definition at line 278 of file odom_tracker.cpp.
References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), m_mutex_, odomFrame_, and updateAggregatedStackPath().
void cl_nav2z::odom_tracker::OdomTracker::setStartPoint | ( | const geometry_msgs::msg::PoseStamped & | pose | ) |
Definition at line 263 of file odom_tracker.cpp.
References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), m_mutex_, and updateAggregatedStackPath().
Referenced by cl_nav2z::CbNavigateBackwards::onEntry(), and cl_nav2z::CbNavigateForward::onEntry().
void cl_nav2z::odom_tracker::OdomTracker::setWorkingMode | ( | WorkingMode | workingMode | ) |
Definition at line 98 of file odom_tracker.cpp.
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().
|
protected |
Definition at line 330 of file odom_tracker.cpp.
References aggregatedStackPathMsg_, odomFrame_, and pathStack_.
Referenced by clearPath(), popPath(), pushPath(), setPublishMessages(), and setStartPoint().
|
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.
References baseTrajectory_, clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getLogger(), and cl_nav2z::odom_tracker::p2pDistance().
Referenced by processOdometryMessage().
|
protected |
reconfigCB()
Definition at line 485 of file odom_tracker.cpp.
References clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getNode(), odomFrame_, recordAngularDistanceThreshold_, and recordPointDistanceThreshold_.
Referenced by processOdometryMessage().
|
protectedvirtual |
Track robot base pose
Definition at line 426 of file odom_tracker.cpp.
References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), cl_nav2z::odom_tracker::p2pDistance(), recordAngularDistanceThreshold_, and recordPointDistanceThreshold_.
Referenced by processOdometryMessage().
|
protected |
Definition at line 163 of file odom_tracker.hpp.
Referenced by rtPublishPaths(), and updateAggregatedStackPath().
|
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().
|
protected |
rads
Definition at line 138 of file odom_tracker.hpp.
Referenced by onInitialize(), setWorkingMode(), updateClearPath(), and updateConfiguration().
|
protected |
rads
Definition at line 135 of file odom_tracker.hpp.
Referenced by onInitialize(), setWorkingMode(), updateClearPath(), and updateConfiguration().
|
protected |
Definition at line 168 of file odom_tracker.hpp.
Referenced by clearPath(), getCurrentMotionGoal(), popPath(), pushPath(), and setCurrentMotionGoal().
|
protected |
Definition at line 169 of file odom_tracker.hpp.
Referenced by logStateString(), pushPath(), and setCurrentPathName().
|
protected |
Definition at line 171 of file odom_tracker.hpp.
Referenced by clearPath(), getCurrentMotionGoal(), getPath(), popPath(), processOdometryMessage(), pushPath(), setCurrentMotionGoal(), setPublishMessages(), setStartPoint(), and setWorkingMode().
|
protected |
Definition at line 140 of file odom_tracker.hpp.
Referenced by OdomTracker(), onInitialize(), setStartPoint(), updateAggregatedStackPath(), and updateConfiguration().
|
protected |
Definition at line 125 of file odom_tracker.hpp.
Referenced by onInitialize().
|
protected |
Definition at line 142 of file odom_tracker.hpp.
Referenced by OdomTracker(), and onInitialize().
|
protected |
Definition at line 161 of file odom_tracker.hpp.
Referenced by logStateString(), popPath(), and pushPath().
|
protected |
Definition at line 153 of file odom_tracker.hpp.
Referenced by logStateString(), popPath(), pushPath(), and updateAggregatedStackPath().
|
protected |
Definition at line 146 of file odom_tracker.hpp.
Referenced by OdomTracker(), processOdometryMessage(), and setPublishMessages().
|
protected |
Meters.
Definition at line 132 of file odom_tracker.hpp.
Referenced by onInitialize(), setWorkingMode(), updateConfiguration(), and updateRecordPath().
|
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().
|
protected |
Definition at line 119 of file odom_tracker.hpp.
Referenced by onInitialize(), and rtPublishPaths().
|
protected |
Definition at line 120 of file odom_tracker.hpp.
Referenced by onInitialize(), and rtPublishPaths().
|
protected |
Definition at line 166 of file odom_tracker.hpp.
Referenced by OdomTracker(), and onInitialize().
|
protected |
Definition at line 151 of file odom_tracker.hpp.
Referenced by OdomTracker(), processOdometryMessage(), and setWorkingMode().