Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #ifndef ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H
00021 #define ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H
00022
00023 #include <ros/ros.h>
00024 #include <robot_calibration/capture/depth_camera.h>
00025 #include <robot_calibration/capture/feature_finder.h>
00026
00027 #include <tf/transform_listener.h>
00028 #include <sensor_msgs/Image.h>
00029 #include <sensor_msgs/PointCloud2.h>
00030 #include <geometry_msgs/PointStamped.h>
00031 #include <robot_calibration_msgs/CalibrationData.h>
00032 #include <robot_calibration_msgs/GripperLedCommandAction.h>
00033 #include <actionlib/client/simple_action_client.h>
00034
00035 namespace robot_calibration
00036 {
00037
00039 class LedFinder : public FeatureFinder
00040 {
00042 struct CloudDifferenceTracker
00043 {
00044
00045 CloudDifferenceTracker(std::string frame, double x, double y, double z);
00046
00057 bool process(sensor_msgs::PointCloud2& cloud,
00058 sensor_msgs::PointCloud2& prev,
00059 geometry_msgs::Point& led_point,
00060 double max_distance,
00061 double weight);
00062
00063
00064 bool isFound(const sensor_msgs::PointCloud2& cloud,
00065 double threshold);
00066
00067
00068 bool getRefinedCentroid(const sensor_msgs::PointCloud2& cloud,
00069 geometry_msgs::PointStamped& centroid);
00070
00071
00072 void reset(size_t height, size_t width);
00073
00074
00075 sensor_msgs::Image getImage();
00076
00077 std::vector<double> diff_;
00078 double max_;
00079 int max_idx_;
00080 int count_;
00081 size_t height_, width_;
00082 std::string frame_;
00083 geometry_msgs::Point point_;
00084 };
00085
00086 typedef actionlib::SimpleActionClient<robot_calibration_msgs::GripperLedCommandAction> LedClient;
00087
00088 public:
00089 LedFinder(ros::NodeHandle & n);
00090
00096 bool find(robot_calibration_msgs::CalibrationData * msg);
00097
00098 private:
00099 void cameraCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud);
00100 bool waitForCloud();
00101
00102 ros::Subscriber subscriber_;
00103 ros::Publisher publisher_;
00104 boost::scoped_ptr<LedClient> client_;
00105
00106 bool waiting_;
00107 sensor_msgs::PointCloud2 cloud_;
00108
00109 std::vector<boost::shared_ptr<ros::Publisher> > tracker_publishers_;
00110 std::vector<CloudDifferenceTracker> trackers_;
00111 std::vector<uint8_t> codes_;
00112
00113 tf::TransformListener listener_;
00114 DepthCameraInfoManager depth_camera_manager_;
00115
00116
00117
00118
00119 double max_error_;
00120 double max_inconsistency_;
00121
00122 double threshold_;
00123 int max_iterations_;
00124
00125 bool output_debug_;
00126
00127 std::string camera_sensor_name_;
00128 std::string chain_sensor_name_;
00129 };
00130
00131 }
00132
00133 #endif // ROBOT_CALIBRATION_CAPTURE_LED_FINDER_H