Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
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]

List of all members.

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)
 Attempts to find the led in incoming data.
 LedFinder (ros::NodeHandle &n)

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?
std::string chain_sensor_name_
boost::scoped_ptr< LedClientclient_
 Outgoing sensor_msgs::PointCloud2.
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.
int max_iterations_
 Minimum value of diffs in order to trigger that this is an LED.
bool output_debug_
 Maximum number of cycles before we abort finding the LED.
ros::Publisher publisher_
 Incoming sensor_msgs::PointCloud2.
ros::Subscriber subscriber_
double threshold_
std::vector< boost::shared_ptr
< ros::Publisher > > 
tracker_publishers_
std::vector
< CloudDifferenceTracker
trackers_
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

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

Definition at line 86 of file led_finder.h.


Constructor & Destructor Documentation

Definition at line 45 of file led_finder.cpp.


Member Function Documentation

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

Definition at line 114 of file led_finder.cpp.

bool robot_calibration::LedFinder::find ( robot_calibration_msgs::CalibrationData *  msg) [virtual]

Attempts to find the led in incoming data.

Parameters:
msgCalibrationData instance to fill in with led point information.
Returns:
True if point has been filled in.

Implements robot_calibration::FeatureFinder.

Definition at line 145 of file led_finder.cpp.

Definition at line 124 of file led_finder.cpp.


Member Data Documentation

Should we output debug image/cloud?

Definition at line 127 of file led_finder.h.

Definition at line 128 of file led_finder.h.

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

Outgoing sensor_msgs::PointCloud2.

Definition at line 104 of file led_finder.h.

sensor_msgs::PointCloud2 robot_calibration::LedFinder::cloud_ [private]

Definition at line 107 of file led_finder.h.

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

Definition at line 111 of file led_finder.h.

Definition at line 114 of file led_finder.h.

Definition at line 113 of file led_finder.h.

Definition at line 119 of file led_finder.h.

Maximum distance led can be from expected pose.

Definition at line 120 of file led_finder.h.

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

Definition at line 123 of file led_finder.h.

Maximum number of cycles before we abort finding the LED.

Definition at line 125 of file led_finder.h.

Incoming sensor_msgs::PointCloud2.

Definition at line 103 of file led_finder.h.

Definition at line 102 of file led_finder.h.

Definition at line 122 of file led_finder.h.

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

Definition at line 109 of file led_finder.h.

Definition at line 110 of file led_finder.h.

Definition at line 106 of file led_finder.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Sat May 20 2017 02:35:31