35 #include <boost/thread/mutex.hpp> 37 #include "opencv2/opencv.hpp" 39 #if ( CV_MAJOR_VERSION >= 4) 40 #include <opencv2/opencv.hpp> 41 #include <opencv2/highgui/highgui_c.h> 42 #include <opencv2/calib3d/calib3d_c.h> 45 #include "sensor_msgs/CameraInfo.h" 46 #include "sensor_msgs/Image.h" 48 #include "posedetection_msgs/ObjectDetection.h" 49 #include "posedetection_msgs/Detect.h" 50 #include "geometry_msgs/PointStamped.h" 51 #include "geometry_msgs/PoseStamped.h" 53 #include "geometry_msgs/PolygonStamped.h" 54 #include "jsk_recognition_msgs/PolygonArray.h" 56 #include <sys/timeb.h> 58 #include <dynamic_reconfigure/server.h> 59 #include <checkerboard_detector/CheckerboardDetectorConfig.h> 70 return vector<T>((istream_iterator<T>(ss)), istream_iterator<T>());
100 int display,
verbose, maxboard, queue_size, publish_queue_size;
110 typedef checkerboard_detector::CheckerboardDetectorConfig
Config;
123 _node.
param(
"display", display, 0);
124 _node.
param(
"verbose", verbose, 1);
125 _node.
param(
"maxboard", maxboard, -1);
126 _node.
param(
"invert_color", invert_color,
false);
127 _node.
param(
"use_P", use_P,
false);
128 _node.
param(
"message_throttle", message_throttle_, 1);
129 _node.
param(
"queue_size", queue_size, 1);
130 _node.
param(
"publish_queue_size", publish_queue_size, 1);
131 _node.
param(
"axis_size", axis_size_, 0.05);
132 _node.
param(
"circle_size", circle_size_, 6);
137 srv = boost::make_shared <dynamic_reconfigure::Server<Config> > (_node);
138 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
140 srv->setCallback (f);
145 sprintf(str,
"grid%d_size_x",index);
149 ROS_ERROR(
"Param: %s must be greater than 2",str);
153 sprintf(str,
"grid%d_size_y",index);
157 ROS_ERROR(
"Param: %s must be greater than 2",str);
161 sprintf(str,
"rect%d_size_x",index);
162 if( !_node.
getParam(str,fRectSize[0]) )
165 sprintf(str,
"rect%d_size_y",index);
166 if( !_node.
getParam(str,fRectSize[1]) )
169 sprintf(str,
"type%d",index);
171 sprintf(str,
"checker%dx%d", dimx, dimy);
175 std::string board_type;
176 _node.
param(
"board_type", board_type, std::string(
"chess"));
179 string strtranslation,strrotation;
180 sprintf(str,
"translation%d",index);
181 _node.
param(str,strtranslation,
string());
183 vector<float> vtranslation = tokenizevector<float>(strtranslation);
184 sprintf(str,
"rotation%d",index);
185 _node.
param(str,strrotation,
string());
187 vector<float> vrotation = tokenizevector<float>(strrotation);
191 cb.board_type = board_type;
192 cb.grid3d.resize(dimx*dimy);
194 if (board_type ==
"chess" || board_type ==
"circle" || board_type ==
"circles") {
195 for(
int y=0;
y<dimy; ++
y)
196 for(
int x=0;
x<dimx; ++
x)
197 cb.grid3d[j++] = cv::Point3f(
x*fRectSize[0],
y*fRectSize[1], 0);
199 else if (board_type ==
"acircle" || board_type ==
"acircles") {
200 for(
int ii=0; ii<dimy; ii++) {
201 for(
int jj=0; jj<dimx; jj++) {
202 cb.grid3d[j++] = cv::Point3f((2*jj + ii % 2)*fRectSize[0],
209 if( vtranslation.size() == 3 )
210 cb.tlocaltrans.trans =
211 Vector(vtranslation[0],vtranslation[1],vtranslation[2]);
213 if( vrotation.size() == 9 ) {
214 for(
int k = 0; k < 3; ++k) {
215 cb.tlocaltrans.m[4*k+0] = vrotation[3*k+0];
216 cb.tlocaltrans.m[4*k+1] = vrotation[3*k+1];
217 cb.tlocaltrans.m[4*k+2] = vrotation[3*k+2];
221 vcheckers.push_back(cb);
222 vstrtypes.push_back(type);
223 maptypes[vstrtypes.back()] = index;
227 _node.
param(
"frame_id", frame_id,
string(
""));
229 if( maptypes.size() == 0 ) {
235 cv::namedWindow(
"Checkerboard Detector",
236 (display == 1? CV_WINDOW_NORMAL : display));
243 _node.
advertise<posedetection_msgs::ObjectDetection> (
"ObjectDetection", publish_queue_size,
244 connect_cb, connect_cb);
246 _node.
advertise<geometry_msgs::PoseStamped> (
"objectdetection_pose", publish_queue_size,
247 connect_cb, connect_cb);
248 _pubCornerPoint = _node.
advertise<geometry_msgs::PointStamped>(
"corner_point", publish_queue_size, connect_cb, connect_cb);
249 _pubPolygonArray = _node.
advertise<jsk_recognition_msgs::PolygonArray>(
"polygons", publish_queue_size, connect_cb, connect_cb);
251 _node.
advertise<sensor_msgs::Image>(
"debug_image", publish_queue_size, connect_cb, connect_cb);
255 _node.
advertise<posedetection_msgs::ObjectDetection> (
"ObjectDetection", publish_queue_size);
257 _node.
advertise<geometry_msgs::PoseStamped> (
"objectdetection_pose", publish_queue_size);
258 _pubCornerPoint = _node.
advertise<geometry_msgs::PointStamped>(
"corner_point", publish_queue_size);
259 _pubPolygonArray = _node.
advertise<jsk_recognition_msgs::PolygonArray>(
"polygons", publish_queue_size);
260 _pubDebugImage = _node.
advertise<sensor_msgs::Image>(
"debug_image", publish_queue_size);
280 boost::mutex::scoped_lock lock(this->mutex);
282 this->_camInfoMsg = *msg;
290 ROS_WARN(
"The topic CameraInfo has been deprecated. Please change your launch file to use camera_info instead.");
296 jsk_recognition_msgs::PolygonArray polygon_array;
297 polygon_array.header = obj.header;
298 for (
size_t i = 0; i < obj.objects.size(); i++) {
299 geometry_msgs::Pose pose = obj.objects[i].pose;
300 Eigen::Affine3d affine;
302 Eigen::Vector3d A_local(0, 0, 0);
303 Eigen::Vector3d B_local((dimx - 1) * fRectSize[0], 0, 0);
304 Eigen::Vector3d C_local((dimx - 1) * fRectSize[0], (dimy - 1) * fRectSize[1], 0);
305 Eigen::Vector3d D_local(0, (dimy - 1) * fRectSize[1], 0);
306 Eigen::Vector3d A_global = affine * A_local;
307 Eigen::Vector3d B_global = affine * B_local;
308 Eigen::Vector3d C_global = affine * C_local;
309 Eigen::Vector3d D_global = affine * D_local;
310 geometry_msgs::Point32 a, b, c,
d;
311 a.x = A_global[0]; a.y = A_global[1]; a.z = A_global[2];
312 b.x = B_global[0]; b.y = B_global[1]; b.z = B_global[2];
313 c.x = C_global[0]; c.y = C_global[1]; c.z = C_global[2];
314 d.x = D_global[0]; d.y = D_global[1]; d.z = D_global[2];
315 geometry_msgs::PolygonStamped polygon;
316 polygon.header = obj.header;
317 polygon.polygon.points.push_back(a);
318 polygon.polygon.points.push_back(b);
319 polygon.polygon.points.push_back(c);
320 polygon.polygon.points.push_back(d);
321 polygon_array.polygons.push_back(polygon);
323 _pubPolygonArray.
publish(polygon_array);
328 ROS_WARN(
"The topic Image has been deprecated. Please change your launch file to use image instead.");
329 boost::mutex::scoped_lock lock(this->mutex);
330 ++message_throttle_counter_;
331 if (message_throttle_counter_ % message_throttle_ == 0) {
332 message_throttle_counter_ = 0;
333 if( Detect(_objdetmsg,*msg,this->_camInfoMsg) ) {
334 if (_objdetmsg.objects.size() > 0) {
335 geometry_msgs::PoseStamped pose;
336 pose.header = _objdetmsg.header;
337 pose.pose = _objdetmsg.objects[0].pose;
340 _pubDetection.
publish(_objdetmsg);
341 publishPolygonArray(_objdetmsg);
348 void image_cb(
const sensor_msgs::ImageConstPtr &msg)
350 boost::mutex::scoped_lock lock(this->mutex);
351 ++message_throttle_counter_;
352 if (message_throttle_counter_ % message_throttle_ == 0) {
353 message_throttle_counter_ = 0;
354 if( Detect(_objdetmsg,*msg,this->_camInfoMsg) ) {
355 if (_objdetmsg.objects.size() > 0) {
356 geometry_msgs::PoseStamped pose;
357 pose.header = _objdetmsg.header;
358 pose.pose = _objdetmsg.objects[0].pose;
361 _pubDetection.
publish(_objdetmsg);
362 publishPolygonArray(_objdetmsg);
367 bool detect_cb(posedetection_msgs::Detect::Request& req, posedetection_msgs::Detect::Response& res)
369 bool result = Detect(res.object_detection,req.image,req.camera_info);
376 if ( camInfoSubscriber == NULL )
377 camInfoSubscriber = _node.
subscribe(
"camera_info", queue_size,
379 if ( imageSubscriber == NULL ) {
380 imageSubscriber = _node.
subscribe(
"image", queue_size,
382 if ( imageSubscriber.
getTopic().find(
"image_rect") != std::string::npos )
383 ROS_WARN(
"topic name seems rectified, please use unrectified image");
385 if ( camInfoSubscriber2 == NULL )
387 if ( imageSubscriber2 == NULL ) {
389 if ( imageSubscriber2.
getTopic().find(
"image_rect") != std::string::npos )
390 ROS_WARN(
"topic name seems rectified, please use unrectified image");
404 boost::mutex::scoped_lock lock(this->mutex);
417 bool Detect(posedetection_msgs::ObjectDetection& objdetmsg,
418 const sensor_msgs::Image& imagemsg,
419 const sensor_msgs::CameraInfo& camInfoMsg)
422 sensor_msgs::CameraInfo cam_info(camInfoMsg);
423 if (cam_info.distortion_model.empty()) {
424 cam_info.distortion_model =
"plumb_bob";
425 cam_info.D.resize(5, 0);
428 for (
size_t i = 0; i < cam_info.D.size(); i++) {
434 if (use_P || std::equal(cam_info.R.begin() + 1, cam_info.R.end(), cam_info.R.begin())) {
441 if (use_P || std::equal(cam_info.K.begin() + 1, cam_info.K.end(), cam_info.K.begin())) {
442 cam_info.K[0] = cam_info.P[0];
443 cam_info.K[1] = cam_info.P[1];
444 cam_info.K[2] = cam_info.P[2];
445 cam_info.K[3] = cam_info.P[4];
446 cam_info.K[4] = cam_info.P[5];
447 cam_info.K[5] = cam_info.P[6];
448 cam_info.K[6] = cam_info.P[8];
449 cam_info.K[7] = cam_info.P[9];
450 cam_info.K[8] = cam_info.P[10];
455 if (imagemsg.encoding ==
"32FC1") {
459 cv::Mat float_image = float_capture->image;
461 float_image.convertTo(mono_image, CV_8UC1);
463 capture_ptr->image = mono_image;
469 ROS_ERROR(
"failed to get image %s", e.what());
472 cv::Mat capture = capture_ptr->image;
474 capture = cv::Mat((capture + 0.0) * 1.0 / 1.0) * 1.0;
477 cv::bitwise_not(capture, tmp);
483 cv::cvtColor(capture, frame, CV_GRAY2BGR);
485 vector<posedetection_msgs::Object6DPose> vobjects;
487 #pragma omp parallel for schedule(dynamic,1) 488 for(
int i = 0; i < (int)vcheckers.size(); ++i) {
490 int ncorners, board=0;
491 posedetection_msgs::Object6DPose objpose;
494 while((maxboard==-1)?1:((++board)<=maxboard)) {
495 bool allfound =
false;
497 allfound = cv::findChessboardCorners(
499 (adaptive_thresh_flag ? CV_CALIB_CB_ADAPTIVE_THRESH : 0) |
500 (normalize_image_flag ? CV_CALIB_CB_NORMALIZE_IMAGE : 0) |
501 (filter_quads_flag ? CV_CALIB_CB_FILTER_QUADS : 0) |
502 (fast_check_flag ? CV_CALIB_CB_FAST_CHECK : 0)
516 cv::CALIB_CB_ASYMMETRIC_GRID | cv::CALIB_CB_CLUSTERING);
523 const int borderthresh = 30;
525 for(
int j = 0; j < ncorners; ++j) {
528 if( x < borderthresh || x > capture.cols - borderthresh ||
529 y < borderthresh || y > capture.rows - borderthresh )
537 cv::Point upperleft, lowerright;
538 upperleft.x = lowerright.x = cb.
corners[0].x;
539 upperleft.y = lowerright.y = cb.
corners[0].y;
540 for(
size_t j = 1; j < cb.
corners.size(); ++j) {
541 if( upperleft.x > cb.
corners[j].x ) upperleft.x = cb.
corners[j].x;
542 if( upperleft.y > cb.
corners[j].y ) upperleft.y = cb.
corners[j].y;
543 if( lowerright.x < cb.
corners[j].x ) lowerright.x = cb.
corners[j].x;
544 if( lowerright.y < cb.
corners[j].y ) lowerright.y = cb.
corners[j].y;
548 (double)( ((upperleft.x - lowerright.x) * (upperleft.x - lowerright.x)) +
549 ((upperleft.y - lowerright.y) * (upperleft.y - lowerright.y)) )
554 ROS_INFO(
"(%d %d) - (%d %d) -> %f ",
555 upperleft.x, upperleft.y, lowerright.x, lowerright.y,
sqrt(step_size));
557 int size = (int)(0.5*
sqrt(step_size) + 0.5);
561 cv::cornerSubPix(capture, cb.
corners,
562 cv::Size(size,size), cv::Size(-1,-1),
563 cv::TermCriteria(CV_TERMCRIT_ITER, 50, 1e-2));
571 vobjects.push_back(objpose);
572 vobjects.back().type = vstrtypes[i];
574 cv::rectangle(capture, upperleft, lowerright,
575 cv::Scalar(0,0,0), CV_FILLED);
582 objdetmsg.objects = vobjects;
583 objdetmsg.header.stamp = imagemsg.header.stamp;
584 if( frame_id.size() > 0 )
585 objdetmsg.header.frame_id = frame_id;
587 objdetmsg.header.frame_id = imagemsg.header.frame_id;
590 ROS_INFO(
"checkerboard: image: %ux%u (size=%u), num: %u, total: %.3fs",
591 imagemsg.width, imagemsg.height,
592 (
unsigned int)imagemsg.data.size(), (
unsigned int)objdetmsg.objects.size(),
597 for(
size_t i = 0; i < vobjects.size(); ++i) {
598 int itype = maptypes[vobjects[i].type];
601 tglobal.trans =
Vector(vobjects[i].pose.position.x,vobjects[i].pose.position.y,vobjects[i].pose.position.z);
602 tglobal.rot =
Vector(vobjects[i].pose.orientation.w,vobjects[i].pose.orientation.x,vobjects[i].pose.orientation.y, vobjects[i].pose.orientation.z);
606 int csize0 = std::max(circle_size_, 6);
607 int cwidth0 = std::max(circle_size_/3, 2);
608 int csize1 = std::max((2*circle_size_)/3, 4);
609 int csize2 = std::max(circle_size_/4, 2);
610 int cwidth1 = std::max(circle_size_/2, 4);
611 int cwidth2 = std::max(circle_size_/2, 3);
613 for(
size_t i = 0; i < cb.
grid3d.size(); ++i) {
615 Vector p = tlocal * grid3d_vec;
616 dReal fx = p.
x*camInfoMsg.P[0] + p.
y*camInfoMsg.P[1] + p.
z*camInfoMsg.P[2] + camInfoMsg.P[3];
617 dReal fy = p.
x*camInfoMsg.P[4] + p.
y*camInfoMsg.P[5] + p.
z*camInfoMsg.P[6] + camInfoMsg.P[7];
618 dReal fz = p.
x*camInfoMsg.P[8] + p.
y*camInfoMsg.P[9] + p.
z*camInfoMsg.P[10] + camInfoMsg.P[11];
619 int x = (int)(fx/fz);
620 int y = (int)(fy/fz);
621 cv::circle(frame, cv::Point(x,y), csize0, cv::Scalar(0, 255, 0), cwidth0);
622 cv::circle(frame, cv::Point(x,y), csize1, cv::Scalar(64*itype,128,128), cwidth1);
623 cv::circle(frame, cv::Point(x,y), csize2, cv::Scalar(0, 0, 0), cwidth0);
630 vaxes[1] =
Vector(axis_size_,0,0);
631 vaxes[2] =
Vector(0,axis_size_,0);
632 vaxes[3] =
Vector(0,0,axis_size_);
634 for(
int i = 0; i < 4; ++i) {
635 Vector p = tglobal*vaxes[i];
636 dReal fx = p.
x*camInfoMsg.P[0] + p.
y*camInfoMsg.P[1] + p.
z*camInfoMsg.P[2] + camInfoMsg.P[3];
637 dReal fy = p.
x*camInfoMsg.P[4] + p.
y*camInfoMsg.P[5] + p.
z*camInfoMsg.P[6] + camInfoMsg.P[7];
638 dReal fz = p.
x*camInfoMsg.P[8] + p.
y*camInfoMsg.P[9] + p.
z*camInfoMsg.P[10] + camInfoMsg.P[11];
639 X[i].x = (int)(fx/fz);
640 X[i].y = (int)(fy/fz);
643 cv::circle(frame, X[0], cwidth2, cv::Scalar(255,255,128), cwidth2);
646 cv::Scalar col0(255,0,(64*itype)%256);
647 cv::Scalar col1(0,255,(64*itype)%256);
648 cv::Scalar col2((64*itype)%256,(64*itype)%256,255);
649 int axis_width_ = floor(axis_size_ / 0.03);
650 cv::line(frame, X[0], X[3], col0, axis_width_);
651 cv::line(frame, X[0], X[2], col1, axis_width_);
652 cv::line(frame, X[0], X[1], col2, axis_width_);
655 geometry_msgs::PointStamped point_msg;
656 point_msg.header = imagemsg.header;
657 point_msg.point.x = X[0].x;
658 point_msg.point.y = X[0].y;
659 point_msg.point.z = vobjects[vobjects.size() - 1].pose.position.z;
660 _pubCornerPoint.
publish(point_msg);
668 cv::imshow(
"Checkerboard Detector",frame);
679 const vector<cv::Point2f> &imgpts,
const vector<cv::Point3f> &objpts,
682 double cell_size = 1.0)
684 geometry_msgs::Pose pose;
686 cv::Mat R3_mat, T3_mat;
687 cv::solvePnP(objpts, imgpts,
690 R3_mat, T3_mat,
false);
692 for (
size_t i = 0; i < 3; i++) {
693 fR3[i] = R3_mat.at<
double>(i);
695 tchecker.trans.x = T3_mat.at<
double>(0);
696 tchecker.trans.y = T3_mat.at<
double>(1);
697 tchecker.trans.z = T3_mat.at<
double>(2);
698 double fang =
sqrt(fR3[0]*fR3[0] + fR3[1]*fR3[1] + fR3[2]*fR3[2]);
700 double fmult =
sin(fang/2)/fang;
701 tchecker.rot =
Vector(
cos(fang/2),fR3[0]*fmult, fR3[1]*fmult, fR3[2]*fmult);
705 cv::Mat projpoints(objpts.size(), 2, CV_32FC1);
707 const cv::Point2f* projpoints_ptr = projpoints.ptr<cv::Point2f>();
708 float max_diff_norm = -10;
709 for (
size_t i = 0; i < objpts.size(); ++i){
710 float diff_norm = (float)norm(imgpts[i] - projpoints_ptr[i]);
711 if (diff_norm > max_diff_norm) {
712 max_diff_norm = diff_norm;
715 ROS_DEBUG(
"max error of cells: %d", max_diff_norm/cell_size);
716 if (max_diff_norm/cell_size > 0.02) {
717 ROS_WARN(
"Large error %f detected, please check (1): checker board is on plane, (2): you uses rectified image", max_diff_norm/cell_size);
721 pose.position.x = tglobal.trans.x;
722 pose.position.y = tglobal.trans.y;
723 pose.position.z = tglobal.trans.z;
724 pose.orientation.x = tglobal.rot.y;
725 pose.orientation.y = tglobal.rot.z;
726 pose.orientation.z = tglobal.rot.w;
727 pose.orientation.w = tglobal.rot.x;
735 boost::mutex::scoped_lock lock(this->mutex);
736 adaptive_thresh_flag = config.adaptive_thresh;
737 normalize_image_flag = config.normalize_image;
738 filter_quads_flag = config.filter_quads;
739 fast_check_flag = config.fast_check;
745 int main(
int argc,
char **argv)
747 ros::init(argc,argv,
"checkerboard_detector");
Defines basic math and gemoetric primitives. dReal is defined in ODE. Any functions not in here like ...
const cv::Matx33d & intrinsicMatrix() const
void image_cb2(const sensor_msgs::ImageConstPtr &msg)
vector< string > vstrtypes
vector< cv::Point2f > corners
int message_throttle_counter_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void image_cb(const sensor_msgs::ImageConstPtr &msg)
ros::Publisher _pubDetection
void publish(const boost::shared_ptr< M > &message) const
geometry_msgs::Pose FindTransformation(const vector< cv::Point2f > &imgpts, const vector< cv::Point3f > &objpts, const Transform &tlocal, const image_geometry::PinholeCameraModel &model, double cell_size=1.0)
ros::Publisher _pubPolygonArray
checkerboard_detector::CheckerboardDetectorConfig Config
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
vector< CHECKERBOARD > vcheckers
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TransformMatrix tlocaltrans
void caminfo_cb(const sensor_msgs::CameraInfoConstPtr &msg)
ros::ServiceServer _srvDetect
int main(int argc, char **argv)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
vector< cv::Point3f > grid3d
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool Detect(posedetection_msgs::ObjectDetection &objdetmsg, const sensor_msgs::Image &imagemsg, const sensor_msgs::CameraInfo &camInfoMsg)
ROSCPP_DECL void spin(Spinner &spinner)
CvSize griddims
number of squares
ros::Publisher _pubCornerPoint
void configCallback(Config &config, uint32_t level)
bool adaptive_thresh_flag
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string TYPE_32FC1
std::string getTopic() const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
RaveTransform< dReal > Transform
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
bool normalize_image_flag
ros::Publisher _pubDebugImage
static vector< T > tokenizevector(const string &s)
ros::Subscriber imageSubscriber2
posedetection_msgs::ObjectDetection _objdetmsg
map< string, int > maptypes
RaveVector< dReal > Vector
uint32_t getNumSubscribers() const
bool getParam(const std::string &key, std::string &s) const
const cv::Mat_< double > & distortionCoeffs() const
void publishPolygonArray(const posedetection_msgs::ObjectDetection &obj)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
ros::Publisher _pubPoseStamped
bool detect_cb(posedetection_msgs::Detect::Request &req, posedetection_msgs::Detect::Response &res)
ros::Subscriber camInfoSubscriber2
virtual ~CheckerboardDetector()
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
sensor_msgs::ImagePtr toImageMsg() const
void caminfo_cb2(const sensor_msgs::CameraInfoConstPtr &msg)
sensor_msgs::CameraInfo _camInfoMsg