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
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #include "ros/ros.h"
00032 #include <sensor_msgs/LaserScan.h>
00033 #include <geometry_msgs/Twist.h>
00034 #include <geometry_msgs/Pose2D.h>
00035 #include <geometry_msgs/PoseArray.h>
00036 #include <opencv2/opencv.hpp>
00037
00038 #ifndef V4R_LASER_ROBOT_CALIBRATION_NODE
00039 #define V4R_LASER_ROBOT_CALIBRATION_NODE
00040
00041
00043 class LaserRobotCalibrationNode {
00044 cv::Matx<float, 3, 3 > Mr2v_;
00045 enum States{
00046 INIT,
00047 ROTATE_TO_MARKER,
00048 ROTATE_NORMAL_TO_MARKER,
00049 };
00050 public:
00051 LaserRobotCalibrationNode ( ros::NodeHandle &n );
00052 void callbackLaser (const sensor_msgs::LaserScan::ConstPtr& msg);
00053 void callbackMarker (const geometry_msgs::PoseArray::ConstPtr& msg);
00054 void stateMashine();
00055 private:
00056 ros::NodeHandle n_;
00057 ros::NodeHandle n_param_;
00058 unsigned callbackCount;
00059 ros::Subscriber sub_laser_;
00060 ros::Subscriber sub_marker_;
00061 ros::Publisher pub_cmd_;
00062 cv::Mat debug_view_;
00063 sensor_msgs::LaserScan msg_scan_;
00064 geometry_msgs::PoseArray msg_marker_;
00065 void draw_debug_view();
00066 void rotateToMarkerNearPoint(cv::Point2f anchor);
00067 cv::Point2f anchor_;
00068 cv::Vec3f marker_;
00069 States state_;
00070
00071 static void mouseCallBack ( int evt, int c, int r, int flags, void *param ) {
00072 if ( evt == CV_EVENT_LBUTTONDOWN ) {
00073 LaserRobotCalibrationNode *pLaserRobotCalibrationNode = (LaserRobotCalibrationNode *) param;
00074 cv::Matx<float, 3, 3 > M = pLaserRobotCalibrationNode->Mr2v_.inv();
00075 cv::Point2f p(c,r);
00076 cv::Point2f anchor(M(0,0)*p.x+M(0,1)*p.y+M(0,2), M(1,0)*p.x+M(1,1)*p.y+M(1,2));
00077 pLaserRobotCalibrationNode->rotateToMarkerNearPoint(anchor);
00078 }
00079 if ( evt == CV_EVENT_MBUTTONDOWN ) {
00080 }
00081 }
00082 };
00083
00084 #endif //V4R_LASER_ROBOT_CALIBRATION_NODE
00085