-
Notifications
You must be signed in to change notification settings - Fork 137
/
Copy patharuco_detect.cpp
707 lines (593 loc) · 24.8 KB
/
aruco_detect.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
/*
* Copyright (c) 2017-19, Ubiquity Robotics Inc., Austin Hendrix
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* The views and conclusions contained in the software and documentation are
* those of the authors and should not be interpreted as representing official
* policies, either expressed or implied, of the FreeBSD Project.
*
*/
#include <assert.h>
#include <sys/time.h>
#include <unistd.h>
#include <ros/ros.h>
#include <tf/transform_datatypes.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <visualization_msgs/Marker.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <dynamic_reconfigure/server.h>
#include <std_srvs/SetBool.h>
#include <std_msgs/String.h>
#include "fiducial_msgs/Fiducial.h"
#include "fiducial_msgs/FiducialArray.h"
#include "fiducial_msgs/FiducialTransform.h"
#include "fiducial_msgs/FiducialTransformArray.h"
#include "aruco_detect/DetectorParamsConfig.h"
#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/calib3d.hpp>
#include <list>
#include <string>
#include <boost/algorithm/string.hpp>
using namespace std;
using namespace cv;
class FiducialsNode {
private:
ros::Publisher * vertices_pub;
ros::Publisher * pose_pub;
ros::Subscriber caminfo_sub;
ros::Subscriber ignore_sub;
image_transport::ImageTransport it;
image_transport::Subscriber img_sub;
ros::ServiceServer service_enable_detections;
// if set, we publish the images that contain fiducials
bool publish_images;
bool enable_detections;
bool subscribe_topics;
double fiducial_len;
bool doPoseEstimation;
bool haveCamInfo;
cv::Mat cameraMatrix;
cv::Mat distortionCoeffs;
int frameNum;
std::string frameId;
std::vector<int> ignoreIds;
std::map<int, double> fiducialLens;
ros::NodeHandle nh;
ros::NodeHandle pnh;
image_transport::Publisher image_pub;
cv::Ptr<aruco::DetectorParameters> detectorParams;
cv::Ptr<aruco::Dictionary> dictionary;
void handleIgnoreString(const std::string& str);
void estimatePoseSingleMarkers(const vector<int> &ids,
const vector<vector<Point2f > >&corners,
float markerLength,
const cv::Mat &cameraMatrix,
const cv::Mat &distCoeffs,
vector<Vec3d>& rvecs, vector<Vec3d>& tvecs,
vector<double>& reprojectionError);
void ignoreCallback(const std_msgs::String &msg);
void imageCallback(const sensor_msgs::ImageConstPtr &msg);
void camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg);
void configCallback(aruco_detect::DetectorParamsConfig &config, uint32_t level);
bool enableDetectionsCallback(std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response &res);
void subscribe();
void unsubscribe();
void subscriberConnectionCallback(const ros::SingleSubscriberPublisher &ssp);
void imageSubscriberConnectionCallback(const image_transport::SingleSubscriberPublisher &ssp);
void subscriberConnectionCallback();
dynamic_reconfigure::Server<aruco_detect::DetectorParamsConfig> configServer;
dynamic_reconfigure::Server<aruco_detect::DetectorParamsConfig>::CallbackType callbackType;
public:
FiducialsNode();
};
/**
* @brief Return object points for the system centered in a single marker, given the marker length
*/
static void getSingleMarkerObjectPoints(float markerLength, vector<Point3f>& objPoints) {
CV_Assert(markerLength > 0);
// set coordinate system in the middle of the marker, with Z pointing out
objPoints.clear();
objPoints.push_back(Vec3f(-markerLength / 2.f, markerLength / 2.f, 0));
objPoints.push_back(Vec3f( markerLength / 2.f, markerLength / 2.f, 0));
objPoints.push_back(Vec3f( markerLength / 2.f,-markerLength / 2.f, 0));
objPoints.push_back(Vec3f(-markerLength / 2.f,-markerLength / 2.f, 0));
}
// Euclidean distance between two points
static double dist(const cv::Point2f &p1, const cv::Point2f &p2)
{
double x1 = p1.x;
double y1 = p1.y;
double x2 = p2.x;
double y2 = p2.y;
double dx = x1 - x2;
double dy = y1 - y2;
return sqrt(dx*dx + dy*dy);
}
// Compute area in image of a fiducial, using Heron's formula
// to find the area of two triangles
static double calcFiducialArea(const std::vector<cv::Point2f> &pts)
{
const Point2f &p0 = pts.at(0);
const Point2f &p1 = pts.at(1);
const Point2f &p2 = pts.at(2);
const Point2f &p3 = pts.at(3);
double a1 = dist(p0, p1);
double b1 = dist(p0, p3);
double c1 = dist(p1, p3);
double a2 = dist(p1, p2);
double b2 = dist(p2, p3);
double c2 = c1;
double s1 = (a1 + b1 + c1) / 2.0;
double s2 = (a2 + b2 + c2) / 2.0;
a1 = sqrt(s1*(s1-a1)*(s1-b1)*(s1-c1));
a2 = sqrt(s2*(s2-a2)*(s2-b2)*(s2-c2));
return a1+a2;
}
// estimate reprojection error
static double getReprojectionError(const vector<Point3f> &objectPoints,
const vector<Point2f> &imagePoints,
const Mat &cameraMatrix, const Mat &distCoeffs,
const Vec3d &rvec, const Vec3d &tvec) {
vector<Point2f> projectedPoints;
cv::projectPoints(objectPoints, rvec, tvec, cameraMatrix,
distCoeffs, projectedPoints);
// calculate RMS image error
double totalError = 0.0;
for (unsigned int i=0; i<objectPoints.size(); i++) {
double error = dist(imagePoints[i], projectedPoints[i]);
totalError += error*error;
}
double rerror = totalError/(double)objectPoints.size();
return rerror;
}
void FiducialsNode::estimatePoseSingleMarkers(const vector<int> &ids,
const vector<vector<Point2f > >&corners,
float markerLength,
const cv::Mat &cameraMatrix,
const cv::Mat &distCoeffs,
vector<Vec3d>& rvecs, vector<Vec3d>& tvecs,
vector<double>& reprojectionError) {
CV_Assert(markerLength > 0);
vector<Point3f> markerObjPoints;
int nMarkers = (int)corners.size();
rvecs.reserve(nMarkers);
tvecs.reserve(nMarkers);
reprojectionError.reserve(nMarkers);
// for each marker, calculate its pose
for (int i = 0; i < nMarkers; i++) {
double fiducialSize = markerLength;
std::map<int, double>::iterator it = fiducialLens.find(ids[i]);
if (it != fiducialLens.end()) {
fiducialSize = it->second;
}
getSingleMarkerObjectPoints(fiducialSize, markerObjPoints);
cv::solvePnP(markerObjPoints, corners[i], cameraMatrix, distCoeffs,
rvecs[i], tvecs[i]);
reprojectionError[i] =
getReprojectionError(markerObjPoints, corners[i],
cameraMatrix, distCoeffs,
rvecs[i], tvecs[i]);
}
}
void FiducialsNode::configCallback(aruco_detect::DetectorParamsConfig & config, uint32_t level)
{
/* Don't load initial config, since it will overwrite the rosparam settings */
if (level == 0xFFFFFFFF) {
return;
}
detectorParams->adaptiveThreshConstant = config.adaptiveThreshConstant;
detectorParams->adaptiveThreshWinSizeMin = config.adaptiveThreshWinSizeMin;
detectorParams->adaptiveThreshWinSizeMax = config.adaptiveThreshWinSizeMax;
detectorParams->adaptiveThreshWinSizeStep = config.adaptiveThreshWinSizeStep;
detectorParams->cornerRefinementMaxIterations = config.cornerRefinementMaxIterations;
detectorParams->cornerRefinementMinAccuracy = config.cornerRefinementMinAccuracy;
detectorParams->cornerRefinementWinSize = config.cornerRefinementWinSize;
#if CV_MINOR_VERSION==2
detectorParams->doCornerRefinement = config.doCornerRefinement;
#else
if (config.doCornerRefinement) {
if (config.cornerRefinementSubpix) {
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
}
else {
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_CONTOUR;
}
}
else {
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_NONE;
}
#endif
detectorParams->errorCorrectionRate = config.errorCorrectionRate;
detectorParams->minCornerDistanceRate = config.minCornerDistanceRate;
detectorParams->markerBorderBits = config.markerBorderBits;
detectorParams->maxErroneousBitsInBorderRate = config.maxErroneousBitsInBorderRate;
detectorParams->minDistanceToBorder = config.minDistanceToBorder;
detectorParams->minMarkerDistanceRate = config.minMarkerDistanceRate;
detectorParams->minMarkerPerimeterRate = config.minMarkerPerimeterRate;
detectorParams->maxMarkerPerimeterRate = config.maxMarkerPerimeterRate;
detectorParams->minOtsuStdDev = config.minOtsuStdDev;
detectorParams->perspectiveRemoveIgnoredMarginPerCell = config.perspectiveRemoveIgnoredMarginPerCell;
detectorParams->perspectiveRemovePixelPerCell = config.perspectiveRemovePixelPerCell;
detectorParams->polygonalApproxAccuracyRate = config.polygonalApproxAccuracyRate;
}
void FiducialsNode::ignoreCallback(const std_msgs::String& msg)
{
ignoreIds.clear();
pnh.setParam("ignore_fiducials", msg.data);
handleIgnoreString(msg.data);
}
void FiducialsNode::camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg)
{
if (haveCamInfo) {
return;
}
if (msg->K != boost::array<double, 9>({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0})) {
for (int i=0; i<3; i++) {
for (int j=0; j<3; j++) {
cameraMatrix.at<double>(i, j) = msg->K[i*3+j];
}
}
for (int i=0; i<5; i++) {
distortionCoeffs.at<double>(0,i) = msg->D[i];
}
haveCamInfo = true;
frameId = msg->header.frame_id;
}
else {
ROS_WARN("%s", "CameraInfo message has invalid intrinsics, K matrix all zeros");
}
}
void FiducialsNode::imageCallback(const sensor_msgs::ImageConstPtr & msg) {
ROS_INFO("Got image %d", msg->header.seq);
frameNum++;
cv_bridge::CvImagePtr cv_ptr;
fiducial_msgs::FiducialTransformArray fta;
fta.header.stamp = msg->header.stamp;
fta.header.frame_id = frameId;
fta.image_seq = msg->header.seq;
fiducial_msgs::FiducialArray fva;
fva.header.stamp = msg->header.stamp;
fva.header.frame_id =frameId;
fva.image_seq = msg->header.seq;
try {
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
vector <int> ids;
vector <vector <Point2f> > corners, rejected;
vector <Vec3d> rvecs, tvecs;
aruco::detectMarkers(cv_ptr->image, dictionary, corners, ids, detectorParams);
ROS_INFO("Detected %d markers", (int)ids.size());
for (size_t i=0; i<ids.size(); i++) {
if (std::count(ignoreIds.begin(), ignoreIds.end(), ids[i]) != 0) {
ROS_INFO("Ignoring id %d", ids[i]);
continue;
}
fiducial_msgs::Fiducial fid;
fid.fiducial_id = ids[i];
fid.x0 = corners[i][0].x;
fid.y0 = corners[i][0].y;
fid.x1 = corners[i][1].x;
fid.y1 = corners[i][1].y;
fid.x2 = corners[i][2].x;
fid.y2 = corners[i][2].y;
fid.x3 = corners[i][3].x;
fid.y3 = corners[i][3].y;
fva.fiducials.push_back(fid);
}
vertices_pub->publish(fva);
if(ids.size() > 0) {
aruco::drawDetectedMarkers(cv_ptr->image, corners, ids);
}
if (doPoseEstimation) {
if (!haveCamInfo) {
if (frameNum > 5) {
ROS_ERROR("No camera intrinsics");
}
return;
}
vector <double>reprojectionError;
estimatePoseSingleMarkers(ids, corners, (float)fiducial_len,
cameraMatrix, distortionCoeffs,
rvecs, tvecs,
reprojectionError);
for (size_t i=0; i<ids.size(); i++) {
aruco::drawAxis(cv_ptr->image, cameraMatrix, distortionCoeffs,
rvecs[i], tvecs[i], (float)fiducial_len);
ROS_INFO("Detected id %d T %.2f %.2f %.2f R %.2f %.2f %.2f", ids[i],
tvecs[i][0], tvecs[i][1], tvecs[i][2],
rvecs[i][0], rvecs[i][1], rvecs[i][2]);
if (std::count(ignoreIds.begin(), ignoreIds.end(), ids[i]) != 0) {
ROS_INFO("Ignoring id %d", ids[i]);
continue;
}
double angle = norm(rvecs[i]);
Vec3d axis = rvecs[i] / angle;
ROS_INFO("angle %f axis %f %f %f",
angle, axis[0], axis[1], axis[2]);
fiducial_msgs::FiducialTransform ft;
ft.fiducial_id = ids[i];
ft.transform.translation.x = tvecs[i][0];
ft.transform.translation.y = tvecs[i][1];
ft.transform.translation.z = tvecs[i][2];
tf2::Quaternion q;
q.setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
ft.transform.rotation.w = q.w();
ft.transform.rotation.x = q.x();
ft.transform.rotation.y = q.y();
ft.transform.rotation.z = q.z();
ft.fiducial_area = calcFiducialArea(corners[i]);
ft.image_error = reprojectionError[i];
// Convert image_error (in pixels) to object_error (in meters)
ft.object_error =
(reprojectionError[i] / dist(corners[i][0], corners[i][2])) *
(norm(tvecs[i]) / fiducial_len);
fta.transforms.push_back(ft);
}
pose_pub->publish(fta);
}
if (publish_images) {
image_pub.publish(cv_ptr->toImageMsg());
}
}
catch(cv_bridge::Exception & e) {
ROS_ERROR("cv_bridge exception: %s", e.what());
}
catch(cv::Exception & e) {
ROS_ERROR("cv exception: %s", e.what());
}
}
void FiducialsNode::handleIgnoreString(const std::string& str)
{
/*
ignogre fiducials can take comma separated list of individual
fiducial ids or ranges, eg "1,4,8,9-12,30-40"
*/
std::vector<std::string> strs;
boost::split(strs, str, boost::is_any_of(","));
for (const string& element : strs) {
if (element == "") {
continue;
}
std::vector<std::string> range;
boost::split(range, element, boost::is_any_of("-"));
if (range.size() == 2) {
int start = std::stoi(range[0]);
int end = std::stoi(range[1]);
ROS_INFO("Ignoring fiducial id range %d to %d", start, end);
for (int j=start; j<=end; j++) {
ignoreIds.push_back(j);
}
}
else if (range.size() == 1) {
int fid = std::stoi(range[0]);
ROS_INFO("Ignoring fiducial id %d", fid);
ignoreIds.push_back(fid);
}
else {
ROS_ERROR("Malformed ignore_fiducials: %s", element.c_str());
}
}
}
bool FiducialsNode::enableDetectionsCallback(std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response &res)
{
enable_detections = req.data;
if (enable_detections)
{
if (vertices_pub->getNumSubscribers() > 0 ||
pose_pub->getNumSubscribers() > 0 ||
image_pub.getNumSubscribers() > 0)
{
subscribe();
}
}
else
{
unsubscribe();
}
if (enable_detections){
res.message = "Enabled aruco detections.";
ROS_INFO("Enabled aruco detections.");
}
else {
res.message = "Disabled aruco detections.";
ROS_INFO("Disabled aruco detections.");
}
res.success = true;
return true;
}
void FiducialsNode::subscriberConnectionCallback(const ros::SingleSubscriberPublisher &ssp)
{
subscriberConnectionCallback();
}
void FiducialsNode::imageSubscriberConnectionCallback(
const image_transport::SingleSubscriberPublisher &ssp)
{
subscriberConnectionCallback();
}
void FiducialsNode::subscriberConnectionCallback()
{
if (!enable_detections) return;
if (vertices_pub->getNumSubscribers() > 0 ||
pose_pub->getNumSubscribers() > 0 ||
image_pub.getNumSubscribers() > 0)
{
subscribe();
}
else if (vertices_pub->getNumSubscribers() == 0 &&
pose_pub->getNumSubscribers() == 0 &&
image_pub.getNumSubscribers() == 0)
{
unsubscribe();
}
}
void FiducialsNode::subscribe()
{
if (!subscribe_topics)
{
subscribe_topics = true;
img_sub = it.subscribe("camera", 1,
&FiducialsNode::imageCallback, this);
caminfo_sub = nh.subscribe("camera_info", 1,
&FiducialsNode::camInfoCallback, this);
ROS_INFO("subscribed camera/camera_info topics");
}
}
void FiducialsNode::unsubscribe()
{
if (subscribe_topics)
{
subscribe_topics = false;
img_sub.shutdown();
caminfo_sub.shutdown();
ROS_INFO("unsubscribed camera/camera_info topics");
}
}
FiducialsNode::FiducialsNode() : nh(), pnh("~"), it(nh)
{
frameNum = 0;
// Camera intrinsics
cameraMatrix = cv::Mat::zeros(3, 3, CV_64F);
// distortion coefficients
distortionCoeffs = cv::Mat::zeros(1, 5, CV_64F);
haveCamInfo = false;
enable_detections = true;
subscribe_topics = false;
int dicno;
detectorParams = new aruco::DetectorParameters();
pnh.param<bool>("publish_images", publish_images, false);
pnh.param<double>("fiducial_len", fiducial_len, 0.14);
pnh.param<int>("dictionary", dicno, 7);
pnh.param<bool>("do_pose_estimation", doPoseEstimation, true);
std::string str;
std::vector<std::string> strs;
pnh.param<string>("ignore_fiducials", str, "");
handleIgnoreString(str);
/*
fiducial size can take comma separated list of size: id or size: range,
e.g. "200.0: 12, 300.0: 200-300"
*/
pnh.param<string>("fiducial_len_override", str, "");
boost::split(strs, str, boost::is_any_of(","));
for (const string& element : strs) {
if (element == "") {
continue;
}
std::vector<std::string> parts;
boost::split(parts, element, boost::is_any_of(":"));
if (parts.size() == 2) {
double len = std::stod(parts[1]);
std::vector<std::string> range;
boost::split(range, element, boost::is_any_of("-"));
if (range.size() == 2) {
int start = std::stoi(range[0]);
int end = std::stoi(range[1]);
ROS_INFO("Setting fiducial id range %d - %d length to %f",
start, end, len);
for (int j=start; j<=end; j++) {
fiducialLens[j] = len;
}
}
else if (range.size() == 1){
int fid = std::stoi(range[0]);
ROS_INFO("Setting fiducial id %d length to %f", fid, len);
fiducialLens[fid] = len;
}
else {
ROS_ERROR("Malformed fiducial_len_override: %s", element.c_str());
}
}
else {
ROS_ERROR("Malformed fiducial_len_override: %s", element.c_str());
}
}
image_transport::SubscriberStatusCallback it_conn_cb = boost::bind(
&FiducialsNode::imageSubscriberConnectionCallback, this, _1);
ros::SubscriberStatusCallback conn_cb = boost::bind(&FiducialsNode::subscriberConnectionCallback,
this, _1);
image_pub = it.advertise("/fiducial_images", 1, it_conn_cb, it_conn_cb);
vertices_pub = new ros::Publisher(nh.advertise<fiducial_msgs::FiducialArray>(
"fiducial_vertices", 1, conn_cb, conn_cb));
pose_pub = new ros::Publisher(nh.advertise<fiducial_msgs::FiducialTransformArray>(
"fiducial_transforms", 1, conn_cb, conn_cb));
dictionary = aruco::getPredefinedDictionary(dicno);
ignore_sub = nh.subscribe("ignore_fiducials", 1,
&FiducialsNode::ignoreCallback, this);
service_enable_detections = nh.advertiseService("enable_detections",
&FiducialsNode::enableDetectionsCallback, this);
callbackType = boost::bind(&FiducialsNode::configCallback, this, _1, _2);
configServer.setCallback(callbackType);
pnh.param<double>("adaptiveThreshConstant", detectorParams->adaptiveThreshConstant, 7);
pnh.param<int>("adaptiveThreshWinSizeMax", detectorParams->adaptiveThreshWinSizeMax, 53); /* defailt 23 */
pnh.param<int>("adaptiveThreshWinSizeMin", detectorParams->adaptiveThreshWinSizeMin, 3);
pnh.param<int>("adaptiveThreshWinSizeStep", detectorParams->adaptiveThreshWinSizeStep, 4); /* default 10 */
pnh.param<int>("cornerRefinementMaxIterations", detectorParams->cornerRefinementMaxIterations, 30);
pnh.param<double>("cornerRefinementMinAccuracy", detectorParams->cornerRefinementMinAccuracy, 0.01); /* default 0.1 */
pnh.param<int>("cornerRefinementWinSize", detectorParams->cornerRefinementWinSize, 5);
#if CV_MINOR_VERSION==2
pnh.param<bool>("doCornerRefinement",detectorParams->doCornerRefinement, true); /* default false */
#else
bool doCornerRefinement = true;
pnh.param<bool>("doCornerRefinement", doCornerRefinement, true);
if (doCornerRefinement) {
bool cornerRefinementSubPix = true;
pnh.param<bool>("cornerRefinementSubPix", cornerRefinementSubPix, true);
if (cornerRefinementSubPix) {
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
}
else {
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_CONTOUR;
}
}
else {
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_NONE;
}
#endif
pnh.param<double>("errorCorrectionRate", detectorParams->errorCorrectionRate , 0.6);
pnh.param<double>("minCornerDistanceRate", detectorParams->minCornerDistanceRate , 0.05);
pnh.param<int>("markerBorderBits", detectorParams->markerBorderBits, 1);
pnh.param<double>("maxErroneousBitsInBorderRate", detectorParams->maxErroneousBitsInBorderRate, 0.04);
pnh.param<int>("minDistanceToBorder", detectorParams->minDistanceToBorder, 3);
pnh.param<double>("minMarkerDistanceRate", detectorParams->minMarkerDistanceRate, 0.05);
pnh.param<double>("minMarkerPerimeterRate", detectorParams->minMarkerPerimeterRate, 0.1); /* default 0.3 */
pnh.param<double>("maxMarkerPerimeterRate", detectorParams->maxMarkerPerimeterRate, 4.0);
pnh.param<double>("minOtsuStdDev", detectorParams->minOtsuStdDev, 5.0);
pnh.param<double>("perspectiveRemoveIgnoredMarginPerCell", detectorParams->perspectiveRemoveIgnoredMarginPerCell, 0.13);
pnh.param<int>("perspectiveRemovePixelPerCell", detectorParams->perspectiveRemovePixelPerCell, 8);
pnh.param<double>("polygonalApproxAccuracyRate", detectorParams->polygonalApproxAccuracyRate, 0.01); /* default 0.05 */
ROS_INFO("Aruco detection ready");
}
int main(int argc, char ** argv) {
ros::init(argc, argv, "aruco_detect");
FiducialsNode* node = new FiducialsNode();
ros::spin();
return 0;
}