This class processes the point cloud input to find the LED. More...
#include <led_finder.h>
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< LedClient > | client_ |
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_ |
This class processes the point cloud input to find the LED.
Definition at line 39 of file led_finder.h.
typedef actionlib::SimpleActionClient<robot_calibration_msgs::GripperLedCommandAction> robot_calibration::LedFinder::LedClient [private] |
Definition at line 86 of file led_finder.h.
Definition at line 45 of file led_finder.cpp.
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.
msg | CalibrationData instance to fill in with led point information. |
Implements robot_calibration::FeatureFinder.
Definition at line 145 of file led_finder.cpp.
bool robot_calibration::LedFinder::waitForCloud | ( | ) | [private] |
Definition at line 124 of file led_finder.cpp.
std::string robot_calibration::LedFinder::camera_sensor_name_ [private] |
Should we output debug image/cloud?
Definition at line 127 of file led_finder.h.
std::string robot_calibration::LedFinder::chain_sensor_name_ [private] |
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.
double robot_calibration::LedFinder::max_error_ [private] |
Definition at line 119 of file led_finder.h.
double robot_calibration::LedFinder::max_inconsistency_ [private] |
Maximum distance led can be from expected pose.
Definition at line 120 of file led_finder.h.
int robot_calibration::LedFinder::max_iterations_ [private] |
Minimum value of diffs in order to trigger that this is an LED.
Definition at line 123 of file led_finder.h.
bool robot_calibration::LedFinder::output_debug_ [private] |
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.
double robot_calibration::LedFinder::threshold_ [private] |
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.
std::vector<CloudDifferenceTracker> robot_calibration::LedFinder::trackers_ [private] |
Definition at line 110 of file led_finder.h.
bool robot_calibration::LedFinder::waiting_ [private] |
Definition at line 106 of file led_finder.h.