Public Member Functions | Private Attributes | List of all members
robot_calibration::FeatureFinder Class Referenceabstract

Base class for a feature finder. More...

#include <feature_finder.h>

Inheritance diagram for robot_calibration::FeatureFinder:
Inheritance graph
[legend]

Public Member Functions

 FeatureFinder ()
 
virtual bool find (robot_calibration_msgs::CalibrationData *msg)=0
 Once the robot has been moved into the proper position and settled, this function will be called. It should add any new observations to the msg passed in. More...
 
std::string getName ()
 Get the name of this feature finder. More...
 
virtual bool init (const std::string &name, ros::NodeHandle &nh)
 Initialize the feature finder. More...
 
virtual ~FeatureFinder ()
 

Private Attributes

std::string name_
 

Detailed Description

Base class for a feature finder.

Definition at line 33 of file feature_finder.h.

Constructor & Destructor Documentation

◆ FeatureFinder()

robot_calibration::FeatureFinder::FeatureFinder ( )
inline

Definition at line 37 of file feature_finder.h.

◆ ~FeatureFinder()

virtual robot_calibration::FeatureFinder::~FeatureFinder ( )
inlinevirtual

Definition at line 38 of file feature_finder.h.

Member Function Documentation

◆ find()

virtual bool robot_calibration::FeatureFinder::find ( robot_calibration_msgs::CalibrationData *  msg)
pure virtual

Once the robot has been moved into the proper position and settled, this function will be called. It should add any new observations to the msg passed in.

Parameters
msgThe message to which observations should be added.
Returns
True if feature finder succeeded in finding the features and adding them to the observation list. False otherwise.

Implemented in robot_calibration::LedFinder, robot_calibration::CheckerboardFinder< T >, robot_calibration::ScanFinder, robot_calibration::PlaneFinder, and robot_calibration::RobotFinder.

◆ getName()

std::string robot_calibration::FeatureFinder::getName ( )
inline

Get the name of this feature finder.

Definition at line 57 of file feature_finder.h.

◆ init()

virtual bool robot_calibration::FeatureFinder::init ( const std::string &  name,
ros::NodeHandle nh 
)
inlinevirtual

Initialize the feature finder.

Parameters
nameThe name of this finder.
nhThe nodehandle to use when loading feature finder configuration data.
Returns
True/False if the feature finder was able to be initialized

Reimplemented in robot_calibration::LedFinder, robot_calibration::CheckerboardFinder< T >, robot_calibration::ScanFinder, robot_calibration::PlaneFinder, and robot_calibration::RobotFinder.

Definition at line 47 of file feature_finder.h.

Member Data Documentation

◆ name_

std::string robot_calibration::FeatureFinder::name_
private

Definition at line 74 of file feature_finder.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01