Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
robot_calibration::LedFinder Class Reference

This class processes the point cloud input to find the LED. More...

#include <led_finder.h>

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

Classes

struct  CloudDifferenceTracker
 Internally used within LED finder to track each of several LEDs. More...
 

Public Member Functions

bool find (robot_calibration_msgs::CalibrationData *msg)
 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...
 
bool init (const std::string &name, ros::NodeHandle &n)
 Initialize the feature finder. More...
 
 LedFinder ()
 
- Public Member Functions inherited from robot_calibration::FeatureFinder
 FeatureFinder ()
 
std::string getName ()
 Get the name of this feature finder. More...
 
virtual ~FeatureFinder ()
 

Private Types

typedef actionlib::SimpleActionClient< robot_calibration_msgs::GripperLedCommandAction > LedClient
 

Private Member Functions

void cameraCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud)
 
bool waitForCloud ()
 

Private Attributes

std::string camera_sensor_name_
 Should we output debug image/cloud? More...
 
std::string chain_sensor_name_
 
boost::scoped_ptr< LedClientclient_
 Outgoing sensor_msgs::PointCloud2. More...
 
sensor_msgs::PointCloud2 cloud_
 
std::vector< uint8_t > codes_
 
DepthCameraInfoManager depth_camera_manager_
 
tf::TransformListener listener_
 
double max_error_
 
double max_inconsistency_
 Maximum distance led can be from expected pose. More...
 
int max_iterations_
 Minimum value of diffs in order to trigger that this is an LED. More...
 
bool output_debug_
 Maximum number of cycles before we abort finding the LED. More...
 
ros::Publisher publisher_
 Incoming sensor_msgs::PointCloud2. More...
 
ros::Subscriber subscriber_
 
double threshold_
 
std::vector< boost::shared_ptr< ros::Publisher > > tracker_publishers_
 
std::vector< CloudDifferenceTrackertrackers_
 
bool waiting_
 

Detailed Description

This class processes the point cloud input to find the LED.

Definition at line 39 of file led_finder.h.

Member Typedef Documentation

◆ LedClient

typedef actionlib::SimpleActionClient<robot_calibration_msgs::GripperLedCommandAction> robot_calibration::LedFinder::LedClient
private

Definition at line 86 of file led_finder.h.

Constructor & Destructor Documentation

◆ LedFinder()

robot_calibration::LedFinder::LedFinder ( )

Definition at line 48 of file led_finder.cpp.

Member Function Documentation

◆ cameraCallback()

void robot_calibration::LedFinder::cameraCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud)
private

Definition at line 126 of file led_finder.cpp.

◆ find()

bool robot_calibration::LedFinder::find ( robot_calibration_msgs::CalibrationData *  msg)
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.

Implements robot_calibration::FeatureFinder.

Definition at line 157 of file led_finder.cpp.

◆ init()

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

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 from robot_calibration::FeatureFinder.

Definition at line 53 of file led_finder.cpp.

◆ waitForCloud()

bool robot_calibration::LedFinder::waitForCloud ( )
private

Definition at line 136 of file led_finder.cpp.

Member Data Documentation

◆ camera_sensor_name_

std::string robot_calibration::LedFinder::camera_sensor_name_
private

Should we output debug image/cloud?

Definition at line 122 of file led_finder.h.

◆ chain_sensor_name_

std::string robot_calibration::LedFinder::chain_sensor_name_
private

Definition at line 123 of file led_finder.h.

◆ client_

boost::scoped_ptr<LedClient> robot_calibration::LedFinder::client_
private

Outgoing sensor_msgs::PointCloud2.

Definition at line 99 of file led_finder.h.

◆ cloud_

sensor_msgs::PointCloud2 robot_calibration::LedFinder::cloud_
private

Definition at line 102 of file led_finder.h.

◆ codes_

std::vector<uint8_t> robot_calibration::LedFinder::codes_
private

Definition at line 106 of file led_finder.h.

◆ depth_camera_manager_

DepthCameraInfoManager robot_calibration::LedFinder::depth_camera_manager_
private

Definition at line 109 of file led_finder.h.

◆ listener_

tf::TransformListener robot_calibration::LedFinder::listener_
private

Definition at line 108 of file led_finder.h.

◆ max_error_

double robot_calibration::LedFinder::max_error_
private

Definition at line 114 of file led_finder.h.

◆ max_inconsistency_

double robot_calibration::LedFinder::max_inconsistency_
private

Maximum distance led can be from expected pose.

Definition at line 115 of file led_finder.h.

◆ max_iterations_

int robot_calibration::LedFinder::max_iterations_
private

Minimum value of diffs in order to trigger that this is an LED.

Definition at line 118 of file led_finder.h.

◆ output_debug_

bool robot_calibration::LedFinder::output_debug_
private

Maximum number of cycles before we abort finding the LED.

Definition at line 120 of file led_finder.h.

◆ publisher_

ros::Publisher robot_calibration::LedFinder::publisher_
private

Incoming sensor_msgs::PointCloud2.

Definition at line 98 of file led_finder.h.

◆ subscriber_

ros::Subscriber robot_calibration::LedFinder::subscriber_
private

Definition at line 97 of file led_finder.h.

◆ threshold_

double robot_calibration::LedFinder::threshold_
private

Definition at line 117 of file led_finder.h.

◆ tracker_publishers_

std::vector<boost::shared_ptr<ros::Publisher> > robot_calibration::LedFinder::tracker_publishers_
private

Definition at line 104 of file led_finder.h.

◆ trackers_

std::vector<CloudDifferenceTracker> robot_calibration::LedFinder::trackers_
private

Definition at line 105 of file led_finder.h.

◆ waiting_

bool robot_calibration::LedFinder::waiting_
private

Definition at line 101 of file led_finder.h.


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


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