Class CpOdomTracker
Defined in File cp_odom_tracker.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public smacc2::ISmaccComponent
Class Documentation
-
class CpOdomTracker : public smacc2::ISmaccComponent
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”
Public Functions
-
CpOdomTracker(std::string odomtopicName = "/odom", std::string odomFrame = "odom")
odom callback: Updates the path - this must be called periodically for each odometry message.
-
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)
Protected Functions
-
void onInitialize() override
-
void updateConfiguration()
-
virtual void rtPublishPaths(rclcpp::Time timestamp)
-
void updateAggregatedStackPath()
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.
-
double recordAngularDistanceThreshold_
Meters.
-
double clearPointDistanceThreshold_
rads
-
double clearAngularDistanceThreshold_
rads
-
std::string odomFrame_
-
std::string odomTopicName_
-
bool publishMessages
-
nav_msgs::msg::Path baseTrajectory_
Processed path for the mouth of the reel.
-
WorkingMode workingMode_
-
std::vector<nav_msgs::msg::Path> pathStack_
-
nav_msgs::msg::Path aggregatedStackPathMsg_
-
bool subscribeToOdometryTopic_
-
std::optional<geometry_msgs::msg::PoseStamped> currentMotionGoal_
-
std::string currentPathName_
-
std::mutex m_mutex_
-
struct PathInfo
-
CpOdomTracker(std::string odomtopicName = "/odom", std::string odomFrame = "odom")