44 #include <visualization_msgs/Marker.h> 48 #include <dynamic_reconfigure/server.h> 49 #include <std_srvs/SetBool.h> 50 #include <std_msgs/String.h> 52 #include "fiducial_msgs/Fiducial.h" 53 #include "fiducial_msgs/FiducialArray.h" 54 #include "fiducial_msgs/FiducialTransform.h" 55 #include "fiducial_msgs/FiducialTransformArray.h" 56 #include "aruco_detect/DetectorParamsConfig.h" 58 #include <vision_msgs/Detection2D.h> 59 #include <vision_msgs/Detection2DArray.h> 60 #include <vision_msgs/ObjectHypothesisWithPose.h> 62 #include <opencv2/highgui.hpp> 63 #include <opencv2/aruco.hpp> 64 #include <opencv2/calib3d.hpp> 68 #include <boost/algorithm/string.hpp> 69 #include <boost/shared_ptr.hpp> 122 void handleIgnoreString(
const std::string& str);
124 void estimatePoseSingleMarkers(
float markerLength,
125 const cv::Mat &cameraMatrix,
126 const cv::Mat &distCoeffs,
127 vector<Vec3d>& rvecs, vector<Vec3d>& tvecs,
128 vector<double>& reprojectionError);
131 void ignoreCallback(
const std_msgs::String &msg);
134 void camInfoCallback(
const sensor_msgs::CameraInfo::ConstPtr &msg);
135 void configCallback(aruco_detect::DetectorParamsConfig &config, uint32_t level);
137 bool enableDetectionsCallback(std_srvs::SetBool::Request &req,
138 std_srvs::SetBool::Response &res);
140 dynamic_reconfigure::Server<aruco_detect::DetectorParamsConfig>
configServer;
141 dynamic_reconfigure::Server<aruco_detect::DetectorParamsConfig>::CallbackType
callbackType;
153 CV_Assert(markerLength > 0);
157 objPoints.push_back(Vec3f(-markerLength / 2.
f, markerLength / 2.
f, 0));
158 objPoints.push_back(Vec3f( markerLength / 2.
f, markerLength / 2.
f, 0));
159 objPoints.push_back(Vec3f( markerLength / 2.
f,-markerLength / 2.
f, 0));
160 objPoints.push_back(Vec3f(-markerLength / 2.
f,-markerLength / 2.
f, 0));
164 static double dist(
const cv::Point2f &p1,
const cv::Point2f &p2)
174 return sqrt(dx*dx + dy*dy);
181 const Point2f &p0 = pts.at(0);
182 const Point2f &p1 = pts.at(1);
183 const Point2f &p2 = pts.at(2);
184 const Point2f &p3 = pts.at(3);
186 double a1 =
dist(p0, p1);
187 double b1 =
dist(p0, p3);
188 double c1 =
dist(p1, p3);
190 double a2 =
dist(p1, p2);
191 double b2 =
dist(p2, p3);
194 double s1 = (a1 + b1 + c1) / 2.0;
195 double s2 = (a2 + b2 + c2) / 2.0;
197 a1 =
sqrt(s1*(s1-a1)*(s1-b1)*(s1-c1));
198 a2 =
sqrt(s2*(s2-a2)*(s2-b2)*(s2-c2));
204 const vector<Point2f> &imagePoints,
205 const Mat &cameraMatrix,
const Mat &distCoeffs,
206 const Vec3d &rvec,
const Vec3d &tvec) {
208 vector<Point2f> projectedPoints;
210 cv::projectPoints(objectPoints, rvec, tvec, cameraMatrix,
211 distCoeffs, projectedPoints);
214 double totalError = 0.0;
215 for (
unsigned int i=0; i<objectPoints.size(); i++) {
216 double error =
dist(imagePoints[i], projectedPoints[i]);
217 totalError += error*error;
219 double rerror = totalError/(double)objectPoints.size();
224 const cv::Mat &cameraMatrix,
225 const cv::Mat &distCoeffs,
226 vector<Vec3d>& rvecs, vector<Vec3d>& tvecs,
227 vector<double>& reprojectionError) {
229 CV_Assert(markerLength > 0);
231 vector<Point3f> markerObjPoints;
232 int nMarkers = (
int)corners.size();
233 rvecs.reserve(nMarkers);
234 tvecs.reserve(nMarkers);
235 reprojectionError.reserve(nMarkers);
238 for (
int i = 0; i < nMarkers; i++) {
239 double fiducialSize = markerLength;
241 std::map<int, double>::iterator it = fiducialLens.find(ids[i]);
242 if (it != fiducialLens.end()) {
243 fiducialSize = it->second;
247 cv::solvePnP(markerObjPoints, corners[i], cameraMatrix, distCoeffs,
250 reprojectionError[i] =
252 cameraMatrix, distCoeffs,
260 if (level == 0xFFFFFFFF) {
264 detectorParams->adaptiveThreshConstant = config.adaptiveThreshConstant;
265 detectorParams->adaptiveThreshWinSizeMin = config.adaptiveThreshWinSizeMin;
266 detectorParams->adaptiveThreshWinSizeMax = config.adaptiveThreshWinSizeMax;
267 detectorParams->adaptiveThreshWinSizeStep = config.adaptiveThreshWinSizeStep;
268 detectorParams->cornerRefinementMaxIterations = config.cornerRefinementMaxIterations;
269 detectorParams->cornerRefinementMinAccuracy = config.cornerRefinementMinAccuracy;
270 detectorParams->cornerRefinementWinSize = config.cornerRefinementWinSize;
271 #if CV_MINOR_VERSION==2 and CV_MAJOR_VERSION==3 272 detectorParams->doCornerRefinement = config.doCornerRefinement;
274 if (config.doCornerRefinement) {
275 if (config.cornerRefinementSubpix) {
276 detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
279 detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_CONTOUR;
283 detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_NONE;
286 detectorParams->errorCorrectionRate = config.errorCorrectionRate;
287 detectorParams->minCornerDistanceRate = config.minCornerDistanceRate;
288 detectorParams->markerBorderBits = config.markerBorderBits;
289 detectorParams->maxErroneousBitsInBorderRate = config.maxErroneousBitsInBorderRate;
290 detectorParams->minDistanceToBorder = config.minDistanceToBorder;
291 detectorParams->minMarkerDistanceRate = config.minMarkerDistanceRate;
292 detectorParams->minMarkerPerimeterRate = config.minMarkerPerimeterRate;
293 detectorParams->maxMarkerPerimeterRate = config.maxMarkerPerimeterRate;
294 detectorParams->minOtsuStdDev = config.minOtsuStdDev;
295 detectorParams->perspectiveRemoveIgnoredMarginPerCell = config.perspectiveRemoveIgnoredMarginPerCell;
296 detectorParams->perspectiveRemovePixelPerCell = config.perspectiveRemovePixelPerCell;
297 detectorParams->polygonalApproxAccuracyRate = config.polygonalApproxAccuracyRate;
303 pnh.setParam(
"ignore_fiducials", msg.data);
304 handleIgnoreString(msg.data);
313 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})) {
314 for (
int i=0; i<3; i++) {
315 for (
int j=0; j<3; j++) {
316 cameraMatrix.at<
double>(i, j) = msg->K[i*3+j];
320 for (
int i=0; i<5; i++) {
321 distortionCoeffs.at<
double>(0,i) = msg->D[i];
325 frameId = msg->header.frame_id;
328 ROS_WARN(
"%s",
"CameraInfo message has invalid intrinsics, K matrix all zeros");
334 if (enable_detections ==
false) {
339 ROS_INFO(
"Got image %d", msg->header.seq);
342 fiducial_msgs::FiducialArray fva;
343 fva.header.stamp = msg->header.stamp;
345 fva.image_seq = msg->header.seq;
350 aruco::detectMarkers(cv_ptr->image, dictionary, corners, ids, detectorParams);
352 int detected_count = (
int)ids.size();
353 if(verbose || detected_count != prev_detected_count){
354 prev_detected_count = detected_count;
355 ROS_INFO(
"Detected %d markers", detected_count);
358 for (
size_t i=0; i<ids.size(); i++) {
359 if (std::count(ignoreIds.begin(), ignoreIds.end(), ids[i]) != 0) {
365 fiducial_msgs::Fiducial fid;
366 fid.fiducial_id = ids[i];
368 fid.x0 = corners[i][0].x;
369 fid.y0 = corners[i][0].y;
370 fid.x1 = corners[i][1].x;
371 fid.y1 = corners[i][1].y;
372 fid.x2 = corners[i][2].x;
373 fid.y2 = corners[i][2].y;
374 fid.x3 = corners[i][3].x;
375 fid.y3 = corners[i][3].y;
376 fva.fiducials.push_back(fid);
379 vertices_pub.publish(fva);
382 aruco::drawDetectedMarkers(cv_ptr->image, corners, ids);
385 if (publish_images) {
386 image_pub.publish(cv_ptr->toImageMsg());
390 ROS_ERROR(
"cv_bridge exception: %s", e.what());
392 catch(cv::Exception & e) {
399 vector <Vec3d> rvecs, tvecs;
401 vision_msgs::Detection2DArray vma;
402 fiducial_msgs::FiducialTransformArray fta;
404 vma.header.stamp = msg->header.stamp;
406 vma.header.seq = msg->header.seq;
409 fta.header.stamp = msg->header.stamp;
411 fta.image_seq = msg->header.seq;
415 if (doPoseEstimation) {
424 vector <double>reprojectionError;
425 estimatePoseSingleMarkers((
float)fiducial_len,
426 cameraMatrix, distortionCoeffs,
430 for (
size_t i=0; i<ids.size(); i++) {
431 aruco::drawAxis(cv_ptr->image, cameraMatrix, distortionCoeffs,
432 rvecs[i], tvecs[i], (
float)fiducial_len);
434 ROS_INFO(
"Detected id %d T %.2f %.2f %.2f R %.2f %.2f %.2f", ids[i],
435 tvecs[i][0], tvecs[i][1], tvecs[i][2],
436 rvecs[i][0], rvecs[i][1], rvecs[i][2]);
440 if (std::count(ignoreIds.begin(), ignoreIds.end(), ids[i]) != 0) {
447 double angle = norm(rvecs[i]);
448 Vec3d axis = rvecs[i] / angle;
452 angle, axis[0], axis[1], axis[2]);
455 double object_error =
456 (reprojectionError[i] /
dist(corners[i][0], corners[i][2])) *
457 (norm(tvecs[i]) / fiducial_len);
460 fiducial_msgs::FiducialTransform ft;
463 vision_msgs::Detection2D vm;
464 vision_msgs::ObjectHypothesisWithPose vmh;
466 vmh.score =
exp(-2 * object_error);
467 vmh.pose.pose.position.x = tvecs[i][0];
468 vmh.pose.pose.position.y = tvecs[i][1];
469 vmh.pose.pose.position.z = tvecs[i][2];
470 q.
setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
471 vmh.pose.pose.orientation.w = q.w();
472 vmh.pose.pose.orientation.x = q.x();
473 vmh.pose.pose.orientation.y = q.y();
474 vmh.pose.pose.orientation.z = q.z();
476 vm.results.push_back(vmh);
477 vma.detections.push_back(vm);
480 ft.fiducial_id = ids[i];
482 ft.transform.translation.x = tvecs[i][0];
483 ft.transform.translation.y = tvecs[i][1];
484 ft.transform.translation.z = tvecs[i][2];
485 q.
setRotation(tf2::Vector3(axis[0], axis[1], axis[2]), angle);
486 ft.transform.rotation.w = q.w();
487 ft.transform.rotation.x = q.x();
488 ft.transform.rotation.y = q.y();
489 ft.transform.rotation.z = q.z();
491 ft.image_error = reprojectionError[i];
494 (reprojectionError[i] /
dist(corners[i][0], corners[i][2])) *
495 (norm(tvecs[i]) / fiducial_len);
497 fta.transforms.push_back(ft);
501 if (publishFiducialTf) {
503 geometry_msgs::TransformStamped ts;
504 ts.transform.translation.x = tvecs[i][0];
505 ts.transform.translation.y = tvecs[i][1];
506 ts.transform.translation.z = tvecs[i][2];
507 ts.transform.rotation.w = q.w();
508 ts.transform.rotation.x = q.x();
509 ts.transform.rotation.y = q.y();
510 ts.transform.rotation.z = q.z();
512 ts.header.stamp = msg->header.stamp;
513 ts.child_frame_id =
"fiducial_" + std::to_string(ids[i]);
514 broadcaster.sendTransform(ts);
517 geometry_msgs::TransformStamped ts;
518 ts.transform = ft.transform;
520 ts.header.stamp = msg->header.stamp;
521 ts.child_frame_id =
"fiducial_" + std::to_string(ft.fiducial_id);
522 broadcaster.sendTransform(ts);
528 ROS_ERROR(
"cv_bridge exception: %s", e.what());
530 catch(cv::Exception & e) {
535 pose_pub.publish(vma);
537 pose_pub.publish(fta);
546 std::vector<std::string> strs;
547 boost::split(strs, str, boost::is_any_of(
","));
548 for (
const string& element : strs) {
552 std::vector<std::string> range;
553 boost::split(range, element, boost::is_any_of(
"-"));
554 if (range.size() == 2) {
555 int start = std::stoi(range[0]);
556 int end = std::stoi(range[1]);
557 ROS_INFO(
"Ignoring fiducial id range %d to %d", start, end);
558 for (
int j=start; j<=end; j++) {
559 ignoreIds.push_back(j);
562 else if (range.size() == 1) {
563 int fid = std::stoi(range[0]);
564 ROS_INFO(
"Ignoring fiducial id %d", fid);
565 ignoreIds.push_back(fid);
568 ROS_ERROR(
"Malformed ignore_fiducials: %s", element.c_str());
574 std_srvs::SetBool::Response &res)
576 enable_detections = req.data;
577 if (enable_detections){
578 res.message =
"Enabled aruco detections.";
579 ROS_INFO(
"Enabled aruco detections.");
582 res.message =
"Disabled aruco detections.";
583 ROS_INFO(
"Disabled aruco detections.");
618 std::vector<std::string> strs;
620 pnh.
param<
string>(
"ignore_fiducials", str,
"");
627 pnh.
param<
string>(
"fiducial_len_override", str,
"");
628 boost::split(strs, str, boost::is_any_of(
","));
629 for (
const string& element : strs) {
633 std::vector<std::string> parts;
634 boost::split(parts, element, boost::is_any_of(
":"));
635 if (parts.size() == 2) {
636 double len = std::stod(parts[1]);
637 std::vector<std::string> range;
638 boost::split(range, element, boost::is_any_of(
"-"));
639 if (range.size() == 2) {
640 int start = std::stoi(range[0]);
641 int end = std::stoi(range[1]);
642 ROS_INFO(
"Setting fiducial id range %d - %d length to %f",
644 for (
int j=start; j<=end; j++) {
648 else if (range.size() == 1){
649 int fid = std::stoi(range[0]);
650 ROS_INFO(
"Setting fiducial id %d length to %f", fid, len);
654 ROS_ERROR(
"Malformed fiducial_len_override: %s", element.c_str());
658 ROS_ERROR(
"Malformed fiducial_len_override: %s", element.c_str());
671 dictionary = aruco::getPredefinedDictionary(dicno);
697 #if CV_MINOR_VERSION==2 and CV_MAJOR_VERSION==3 700 bool doCornerRefinement =
true;
701 pnh.
param<
bool>(
"doCornerRefinement", doCornerRefinement,
true);
702 if (doCornerRefinement) {
703 bool cornerRefinementSubPix =
true;
704 pnh.
param<
bool>(
"cornerRefinementSubPix", cornerRefinementSubPix,
true);
705 if (cornerRefinementSubPix) {
706 detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
709 detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_CONTOUR;
713 detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_NONE;
725 pnh.
param<
double>(
"perspectiveRemoveIgnoredMarginPerCell",
detectorParams->perspectiveRemoveIgnoredMarginPerCell, 0.13);
732 int main(
int argc,
char ** argv) {
void ignoreCallback(const std_msgs::String &msg)
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
ros::Subscriber caminfo_sub
image_transport::Subscriber img_sub
cv::Ptr< aruco::DetectorParameters > detectorParams
dynamic_reconfigure::Server< aruco_detect::DetectorParamsConfig >::CallbackType callbackType
dynamic_reconfigure::Server< aruco_detect::DetectorParamsConfig > configServer
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
ros::ServiceServer service_enable_detections
void configCallback(aruco_detect::DetectorParamsConfig &config, uint32_t level)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
std::map< int, double > fiducialLens
std::string * frameId(M &m)
ros::Subscriber vertices_sub
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::ImageTransport it
cv::Ptr< aruco::Dictionary > dictionary
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::vector< int > ignoreIds
int main(int argc, char **argv)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ros::Subscriber ignore_sub
void handleIgnoreString(const std::string &str)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static double getReprojectionError(const vector< Point3f > &objectPoints, const vector< Point2f > &imagePoints, const Mat &cameraMatrix, const Mat &distCoeffs, const Vec3d &rvec, const Vec3d &tvec)
cv_bridge::CvImagePtr cv_ptr
boost::shared_ptr< fiducial_msgs::FiducialArray const > FiducialArrayConstPtr
void poseEstimateCallback(const FiducialArrayConstPtr &msg)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
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)
vector< vector< Point2f > > corners
INLINE Rall1d< T, V, S > exp(const Rall1d< T, V, S > &arg)
void setRotation(const Vector3 &axis, const tf2Scalar &angle)
image_transport::Publisher image_pub
static double calcFiducialArea(const std::vector< cv::Point2f > &pts)
void estimatePoseSingleMarkers(float markerLength, const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, vector< Vec3d > &rvecs, vector< Vec3d > &tvecs, vector< double > &reprojectionError)
void camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
static void getSingleMarkerObjectPoints(float markerLength, vector< Point3f > &objPoints)
Return object points for the system centered in a single marker, given the marker length...
tf2_ros::TransformBroadcaster broadcaster
bool enableDetectionsCallback(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
ros::Publisher vertices_pub
static double dist(const cv::Point2f &p1, const cv::Point2f &p2)