20 #ifndef ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H 21 #define ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H 28 #include <sensor_msgs/Image.h> 29 #include <sensor_msgs/PointCloud2.h> 30 #include <geometry_msgs/PointStamped.h> 31 #include <robot_calibration_msgs/CalibrationData.h> 32 #include <robot_calibration_msgs/GripperLedCommandAction.h> 57 bool process(sensor_msgs::PointCloud2& cloud,
58 sensor_msgs::PointCloud2& prev,
59 geometry_msgs::Point& led_point,
64 bool isFound(
const sensor_msgs::PointCloud2& cloud,
69 geometry_msgs::PointStamped& centroid);
72 void reset(
size_t height,
size_t width);
91 bool find(robot_calibration_msgs::CalibrationData * msg);
94 void cameraCallback(
const sensor_msgs::PointCloud2::ConstPtr& cloud);
128 #endif // ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H bool getRefinedCentroid(const sensor_msgs::PointCloud2 &cloud, geometry_msgs::PointStamped ¢roid)
This class processes the point cloud input to find the LED.
Base class for a feature finder.
sensor_msgs::Image getImage()
DepthCameraInfoManager depth_camera_manager_
std::string camera_sensor_name_
Should we output debug image/cloud?
int max_iterations_
Minimum value of diffs in order to trigger that this is an LED.
CloudDifferenceTracker(std::string frame, double x, double y, double z)
tf::TransformListener listener_
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< CloudDifferenceTracker > trackers_
std::string chain_sensor_name_
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.
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
std::vector< double > diff_
void cameraCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud)
geometry_msgs::Point point_
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< uint8_t > codes_
bool output_debug_
Maximum number of cycles before we abort finding the LED.
Calibration code lives under this namespace.
sensor_msgs::PointCloud2 cloud_
TFSIMD_FORCE_INLINE const tfScalar & z() const
Base class for a feature finder.
bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called...
Internally used within LED finder to track each of several LEDs.
boost::scoped_ptr< LedClient > client_
Outgoing sensor_msgs::PointCloud2.
std::vector< boost::shared_ptr< ros::Publisher > > tracker_publishers_
ros::Publisher publisher_
Incoming sensor_msgs::PointCloud2.
bool isFound(const sensor_msgs::PointCloud2 &cloud, double threshold)
actionlib::SimpleActionClient< robot_calibration_msgs::GripperLedCommandAction > LedClient
double max_inconsistency_
Maximum distance led can be from expected pose.
ros::Subscriber subscriber_
void reset(size_t height, size_t width)