Public Member Functions | Private Attributes | List of all members
laser_joint_processor::LaserJointProcessor Class Reference

#include <laser_joint_processor.h>

Public Member Functions

bool addJointState (const sensor_msgs::JointStateConstPtr &joint_state)
 
ros::Time getEarliestJointStateTime () const
 
ros::Time getLatestJointStateTime () const
 
bool isSnapshotEarly (const calibration_msgs::DenseLaserSnapshot &snapshot) const
 
bool isSnapshotLate (const calibration_msgs::DenseLaserSnapshot &snapshot) const
 
 LaserJointProcessor ()
 
bool processLaserData (const calibration_msgs::DenseLaserSnapshot &snapshot, const calibration_msgs::CalibrationPattern &features, calibration_msgs::JointStateCalibrationPattern &result, const ros::Duration &max_interp=ros::Duration(.25))
 
void setCacheSize (unsigned int max_size)
 
void setJointNames (const std::vector< std::string > &joint_names)
 

Private Attributes

joint_states_settler::JointStatesDeflater deflater_
 
JointImager imager_
 
JointImageInterpolator interp_
 
std::vector< std::string > joint_names_
 
settlerlib::SortedDeque< joint_states_settler::DeflatedJointStatesjoint_state_cache_
 

Detailed Description

Definition at line 51 of file laser_joint_processor.h.

Constructor & Destructor Documentation

LaserJointProcessor::LaserJointProcessor ( )

Definition at line 43 of file laser_joint_processor.cpp.

Member Function Documentation

bool LaserJointProcessor::addJointState ( const sensor_msgs::JointStateConstPtr &  joint_state)

Definition at line 59 of file laser_joint_processor.cpp.

ros::Time laser_joint_processor::LaserJointProcessor::getEarliestJointStateTime ( ) const
ros::Time laser_joint_processor::LaserJointProcessor::getLatestJointStateTime ( ) const
bool LaserJointProcessor::isSnapshotEarly ( const calibration_msgs::DenseLaserSnapshot &  snapshot) const

Definition at line 69 of file laser_joint_processor.cpp.

bool LaserJointProcessor::isSnapshotLate ( const calibration_msgs::DenseLaserSnapshot &  snapshot) const

Definition at line 92 of file laser_joint_processor.cpp.

bool LaserJointProcessor::processLaserData ( const calibration_msgs::DenseLaserSnapshot &  snapshot,
const calibration_msgs::CalibrationPattern &  features,
calibration_msgs::JointStateCalibrationPattern &  result,
const ros::Duration max_interp = ros::Duration(.25) 
)

Definition at line 117 of file laser_joint_processor.cpp.

void LaserJointProcessor::setCacheSize ( unsigned int  max_size)

Definition at line 48 of file laser_joint_processor.cpp.

void LaserJointProcessor::setJointNames ( const std::vector< std::string > &  joint_names)

Definition at line 53 of file laser_joint_processor.cpp.

Member Data Documentation

joint_states_settler::JointStatesDeflater laser_joint_processor::LaserJointProcessor::deflater_
private

Definition at line 75 of file laser_joint_processor.h.

JointImager laser_joint_processor::LaserJointProcessor::imager_
private

Definition at line 76 of file laser_joint_processor.h.

JointImageInterpolator laser_joint_processor::LaserJointProcessor::interp_
private

Definition at line 77 of file laser_joint_processor.h.

std::vector<std::string> laser_joint_processor::LaserJointProcessor::joint_names_
private

Definition at line 78 of file laser_joint_processor.h.

settlerlib::SortedDeque<joint_states_settler::DeflatedJointStates> laser_joint_processor::LaserJointProcessor::joint_state_cache_
private

Definition at line 74 of file laser_joint_processor.h.


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


laser_joint_processor
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:55