Public Member Functions | Public Attributes
robot_calibration::LedFinder::CloudDifferenceTracker Struct Reference

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

List of all members.

Public Member Functions

 CloudDifferenceTracker (std::string frame, double x, double y, double z)
sensor_msgs::Image getImage ()
bool getRefinedCentroid (const sensor_msgs::PointCloud2 &cloud, geometry_msgs::PointStamped &centroid)
bool isFound (const sensor_msgs::PointCloud2 &cloud, double threshold)
bool process (sensor_msgs::PointCloud2 &cloud, sensor_msgs::PointCloud2 &prev, geometry_msgs::Point &led_point, double max_distance, double weight)
 Update the tracker based on new cloud compared to previous.
void reset (size_t height, size_t width)

Public Attributes

int count_
std::vector< double > diff_
std::string frame_
size_t height_
double max_
int max_idx_
geometry_msgs::Point point_
size_t width_

Detailed Description

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

Definition at line 42 of file led_finder.h.


Constructor & Destructor Documentation

robot_calibration::LedFinder::CloudDifferenceTracker::CloudDifferenceTracker ( std::string  frame,
double  x,
double  y,
double  z 
)

Definition at line 336 of file led_finder.cpp.


Member Function Documentation

Definition at line 532 of file led_finder.cpp.

bool robot_calibration::LedFinder::CloudDifferenceTracker::getRefinedCentroid ( const sensor_msgs::PointCloud2 &  cloud,
geometry_msgs::PointStamped &  centroid 
)

Definition at line 468 of file led_finder.cpp.

bool robot_calibration::LedFinder::CloudDifferenceTracker::isFound ( const sensor_msgs::PointCloud2 &  cloud,
double  threshold 
)

Definition at line 443 of file led_finder.cpp.

bool robot_calibration::LedFinder::CloudDifferenceTracker::process ( sensor_msgs::PointCloud2 &  cloud,
sensor_msgs::PointCloud2 &  prev,
geometry_msgs::Point led_point,
double  max_distance,
double  weight 
)

Update the tracker based on new cloud compared to previous.

Parameters:
cloudThe newest cloud
prevThe previous cloud
led_pointThe expected pose of this led in cloud frame
max_distanceThe maximum distance from expected led pose that we should consider changes.
weightWhether the change between frames should increase or decrease the LED point values. Should be +/- 1 typically.

Definition at line 367 of file led_finder.cpp.

void robot_calibration::LedFinder::CloudDifferenceTracker::reset ( size_t  height,
size_t  width 
)

Definition at line 345 of file led_finder.cpp.


Member Data Documentation

Definition at line 80 of file led_finder.h.

Definition at line 77 of file led_finder.h.

Definition at line 82 of file led_finder.h.

Definition at line 81 of file led_finder.h.

Definition at line 78 of file led_finder.h.

Definition at line 79 of file led_finder.h.

Definition at line 83 of file led_finder.h.

Definition at line 81 of file led_finder.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 21:54:10