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

Class to update the pose of the vehicle. More...

#include <base_pose_updater.hpp>

Inheritance diagram for PoseUpdater:
Inheritance graph
Collaboration diagram for PoseUpdater:
Collaboration graph

Classes

struct  TimedPose
 

Public Member Functions

 PoseUpdater (const SLAMParameters &params)
 
 PoseUpdater (const PoseUpdater &other)
 
PoseUpdateroperator= (const PoseUpdater &other)
 
virtual ~PoseUpdater ()
 
virtual std::shared_ptr< PoseUpdaterclone () const
 Class to update the pose of the vehicle.
 
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.
 
virtual bool pose_ready_for_graph_update () const
 Check if the pose is ready for graph update.
 
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
 

Protected Attributes

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.

This class is the one to apply the motion model and keep track of the most up to date pose. It allows for the pose estimate to be calculated independently of the graph optimization, and only update the graph when needed.

Definition at line 18 of file base_pose_updater.hpp.

Constructor & Destructor Documentation

◆ PoseUpdater() [1/2]

PoseUpdater::PoseUpdater ( const SLAMParameters params)
explicit

Definition at line 5 of file base_pose_updater.cpp.

◆ PoseUpdater() [2/2]

PoseUpdater::PoseUpdater ( const PoseUpdater other)

Definition at line 14 of file base_pose_updater.cpp.

◆ ~PoseUpdater()

PoseUpdater::~PoseUpdater ( )
virtualdefault

Member Function Documentation

◆ clone()

std::shared_ptr< PoseUpdater > PoseUpdater::clone ( ) const
virtual

Class to update the pose of the vehicle.

This class is the one to apply the motion model and keep track of the most up to date pose. It allows for the pose estimate to be calculated independently of the graph optimization, and only update the graph when needed.

Reimplemented in DifferenceBasedReadyPoseUpdater, and DoublePoseUpdater.

Definition at line 39 of file base_pose_updater.cpp.

◆ get_adjoint_operator_matrix()

Eigen::Matrix3d PoseUpdater::get_adjoint_operator_matrix ( double  x_translation,
double  y_translation,
double  rotation_angle 
) const

Definition at line 121 of file base_pose_updater.cpp.

Here is the caller graph for this function:

◆ get_last_graphed_pose()

Eigen::Vector3d PoseUpdater::get_last_graphed_pose ( ) const
inline

Definition at line 82 of file base_pose_updater.hpp.

◆ get_last_pose()

Eigen::Vector3d PoseUpdater::get_last_pose ( ) const
inline

Definition at line 80 of file base_pose_updater.hpp.

◆ get_last_pose_update()

rclcpp::Time PoseUpdater::get_last_pose_update ( ) const
inline

Definition at line 89 of file base_pose_updater.hpp.

◆ get_pose_at_timestamp()

Eigen::Vector3d PoseUpdater::get_pose_at_timestamp ( const rclcpp::Time &  timestamp) const

Definition at line 43 of file base_pose_updater.cpp.

◆ get_pose_difference_noise()

Eigen::Vector3d PoseUpdater::get_pose_difference_noise ( ) const
inline

Definition at line 84 of file base_pose_updater.hpp.

◆ operator=()

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

Definition at line 23 of file base_pose_updater.cpp.

Here is the caller graph for this function:

◆ pose_buffer_capacity()

size_t PoseUpdater::pose_buffer_capacity ( ) const
inline

Definition at line 92 of file base_pose_updater.hpp.

◆ pose_buffer_size()

size_t PoseUpdater::pose_buffer_size ( ) const
inline

Definition at line 91 of file base_pose_updater.hpp.

◆ pose_ready_for_graph_update()

bool PoseUpdater::pose_ready_for_graph_update ( ) const
virtual

Check if the pose is ready for graph update.

Returns
true if there is a new pose different from the graph, false otherwise

Reimplemented in DifferenceBasedReadyPoseUpdater.

Definition at line 119 of file base_pose_updater.cpp.

◆ predict_pose()

void PoseUpdater::predict_pose ( const MotionData motion_data,
std::shared_ptr< V2PMotionModel motion_model 
)
virtual

Updates the last pose and returns the pose difference.

Parameters
motion_dataMotion data containing the velocities and timestamp
motion_modelMotion model to apply the velocities

Reimplemented in DoublePoseUpdater.

Definition at line 71 of file base_pose_updater.cpp.

Here is the call graph for this function:

◆ update_pose()

void PoseUpdater::update_pose ( const Eigen::Vector3d &  last_pose)
virtual

Updates the last pose with the given pose.

This method is used to set the last pose directly, for example after an optimization or when the pose is known from another source. It resets the accumulated pose difference.

Parameters
last_poseThe last pose to set

Definition at line 60 of file base_pose_updater.cpp.

Member Data Documentation

◆ _last_graphed_pose_

Eigen::Vector3d PoseUpdater::_last_graphed_pose_
protected

Definition at line 30 of file base_pose_updater.hpp.

◆ _last_pose_

Eigen::Vector3d PoseUpdater::_last_pose_
protected

Definition at line 29 of file base_pose_updater.hpp.

◆ _last_pose_covariance_

Eigen::Matrix3d PoseUpdater::_last_pose_covariance_
protected

Definition at line 31 of file base_pose_updater.hpp.

◆ _last_pose_update_

rclcpp::Time PoseUpdater::_last_pose_update_
protected

Definition at line 32 of file base_pose_updater.hpp.

◆ _new_pose_from_graph_

bool PoseUpdater::_new_pose_from_graph_ = false
protected

Definition at line 35 of file base_pose_updater.hpp.

◆ _pose_buffer_

CircularBuffer<TimedPose> PoseUpdater::_pose_buffer_
protected

Definition at line 37 of file base_pose_updater.hpp.

◆ _received_first_motion_data_

bool PoseUpdater::_received_first_motion_data_ = false
protected

Definition at line 34 of file base_pose_updater.hpp.


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