Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
DifferenceBasedReadyPoseUpdater Class Reference

Class to update the pose of the vehicle, including a method to check if the pose is ready for graph update depending on the accumulated pose difference. More...

#include <difference_based_ready_pose_updater.hpp>

Inheritance diagram for DifferenceBasedReadyPoseUpdater:
Inheritance graph
Collaboration diagram for DifferenceBasedReadyPoseUpdater:
Collaboration graph

Public Member Functions

 DifferenceBasedReadyPoseUpdater (const SLAMParameters &params)
 
 DifferenceBasedReadyPoseUpdater (const DifferenceBasedReadyPoseUpdater &other)
 
DifferenceBasedReadyPoseUpdateroperator= (const DifferenceBasedReadyPoseUpdater &other)
 
virtual ~DifferenceBasedReadyPoseUpdater ()
 
virtual std::shared_ptr< PoseUpdaterclone () const override
 Clone the pose updater.
 
virtual bool pose_ready_for_graph_update () const override
 Check if the accumulated pose difference is greater than the minimum threshold.
 
- Public Member Functions inherited from PoseUpdater
 PoseUpdater (const SLAMParameters &params)
 
 PoseUpdater (const PoseUpdater &other)
 
PoseUpdateroperator= (const PoseUpdater &other)
 
virtual ~PoseUpdater ()
 
virtual void predict_pose (const MotionData &motion_data, std::shared_ptr< V2PMotionModel > motion_model)
 Updates the last pose and returns the pose difference.
 
virtual void update_pose (const Eigen::Vector3d &last_pose)
 Updates the last pose with the given pose.
 
Eigen::Matrix3d get_adjoint_operator_matrix (double x_translation, double y_translation, double rotation_angle) const
 
Eigen::Vector3d get_last_pose () const
 
Eigen::Vector3d get_last_graphed_pose () const
 
Eigen::Vector3d get_pose_difference_noise () const
 
rclcpp::Time get_last_pose_update () const
 
size_t pose_buffer_size () const
 
size_t pose_buffer_capacity () const
 
Eigen::Vector3d get_pose_at_timestamp (const rclcpp::Time &timestamp) const
 

Private Attributes

double minimum_pose_difference_ = 0.3
 

Additional Inherited Members

- Protected Attributes inherited from PoseUpdater
Eigen::Vector3d _last_pose_
 
Eigen::Vector3d _last_graphed_pose_
 
Eigen::Matrix3d _last_pose_covariance_
 
rclcpp::Time _last_pose_update_
 
bool _received_first_motion_data_ = false
 
bool _new_pose_from_graph_ = false
 
CircularBuffer< TimedPose_pose_buffer_
 

Detailed Description

Class to update the pose of the vehicle, including a method to check if the pose is ready for graph update depending on the accumulated pose difference.

This class is the one to apply the motion model and keep track of the most up to date pose. The pose is considered ready for graph update if the accumulated pose difference is greater than a minimum threshold

Definition at line 18 of file difference_based_ready_pose_updater.hpp.

Constructor & Destructor Documentation

◆ DifferenceBasedReadyPoseUpdater() [1/2]

DifferenceBasedReadyPoseUpdater::DifferenceBasedReadyPoseUpdater ( const SLAMParameters params)
explicit

Definition at line 5 of file difference_based_ready_pose_updater.cpp.

◆ DifferenceBasedReadyPoseUpdater() [2/2]

DifferenceBasedReadyPoseUpdater::DifferenceBasedReadyPoseUpdater ( const DifferenceBasedReadyPoseUpdater other)

Definition at line 10 of file difference_based_ready_pose_updater.cpp.

◆ ~DifferenceBasedReadyPoseUpdater()

DifferenceBasedReadyPoseUpdater::~DifferenceBasedReadyPoseUpdater ( )
virtualdefault

Member Function Documentation

◆ clone()

std::shared_ptr< PoseUpdater > DifferenceBasedReadyPoseUpdater::clone ( ) const
overridevirtual

Clone the pose updater.

This method is used to create a copy of the pose updater It is useful for polymorphic classes that use pointers to base class

Returns
A shared pointer to the cloned pose updater

Reimplemented from PoseUpdater.

Reimplemented in DoublePoseUpdater.

Definition at line 29 of file difference_based_ready_pose_updater.cpp.

◆ operator=()

DifferenceBasedReadyPoseUpdater & DifferenceBasedReadyPoseUpdater::operator= ( const DifferenceBasedReadyPoseUpdater other)

Definition at line 18 of file difference_based_ready_pose_updater.cpp.

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

◆ pose_ready_for_graph_update()

bool DifferenceBasedReadyPoseUpdater::pose_ready_for_graph_update ( ) const
overridevirtual

Check if the accumulated pose difference is greater than the minimum threshold.

Returns
true if the pose is ready for graph update, false otherwise

Reimplemented from PoseUpdater.

Definition at line 33 of file difference_based_ready_pose_updater.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ minimum_pose_difference_

double DifferenceBasedReadyPoseUpdater::minimum_pose_difference_ = 0.3
private

Definition at line 19 of file difference_based_ready_pose_updater.hpp.


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