45
45
#include < cv_bridge/cv_bridge.h>
46
46
#include < sensor_msgs/image_encodings.h>
47
47
#include < dynamic_reconfigure/server.h>
48
+ #include < std_srvs/SetBool.h>
48
49
49
50
#include " fiducial_msgs/Fiducial.h"
50
51
#include " fiducial_msgs/FiducialArray.h"
@@ -72,8 +73,11 @@ class FiducialsNode {
72
73
image_transport::ImageTransport it;
73
74
image_transport::Subscriber img_sub;
74
75
76
+ ros::ServiceServer service_enable_detections;
77
+
75
78
// if set, we publish the images that contain fiducials
76
79
bool publish_images;
80
+ bool enable_detections;
77
81
78
82
double fiducial_len;
79
83
@@ -86,7 +90,6 @@ class FiducialsNode {
86
90
std::vector<int > ignoreIds;
87
91
std::map<int , double > fiducialLens;
88
92
89
-
90
93
image_transport::Publisher image_pub;
91
94
92
95
cv::Ptr<aruco::DetectorParameters> detectorParams;
@@ -105,6 +108,9 @@ class FiducialsNode {
105
108
void camInfoCallback (const sensor_msgs::CameraInfo::ConstPtr &msg);
106
109
void configCallback (aruco_detect::DetectorParamsConfig &config, uint32_t level);
107
110
111
+ bool enableDetectionsCallback (std_srvs::SetBool::Request &req,
112
+ std_srvs::SetBool::Response &res);
113
+
108
114
dynamic_reconfigure::Server<aruco_detect::DetectorParamsConfig> configServer;
109
115
dynamic_reconfigure::Server<aruco_detect::DetectorParamsConfig>::CallbackType callbackType;
110
116
@@ -293,6 +299,10 @@ void FiducialsNode::camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg
293
299
}
294
300
295
301
void FiducialsNode::imageCallback (const sensor_msgs::ImageConstPtr & msg) {
302
+ if (enable_detections == false ) {
303
+ return ; // return without doing anything
304
+ }
305
+
296
306
ROS_INFO (" Got image %d" , msg->header .seq );
297
307
frameNum++;
298
308
@@ -411,6 +421,23 @@ void FiducialsNode::imageCallback(const sensor_msgs::ImageConstPtr & msg) {
411
421
}
412
422
}
413
423
424
+ bool FiducialsNode::enableDetectionsCallback (std_srvs::SetBool::Request &req,
425
+ std_srvs::SetBool::Response &res)
426
+ {
427
+ enable_detections = req.data ;
428
+ if (enable_detections){
429
+ res.message = " Enabled aruco detections." ;
430
+ ROS_INFO (" Enabled aruco detections." );
431
+ }
432
+ else {
433
+ res.message = " Disabled aruco detections." ;
434
+ ROS_INFO (" Disabled aruco detections." );
435
+ }
436
+
437
+ res.success = true ;
438
+ return true ;
439
+ }
440
+
414
441
FiducialsNode::FiducialsNode (ros::NodeHandle & nh) : it(nh)
415
442
{
416
443
frameNum = 0 ;
@@ -422,6 +449,7 @@ FiducialsNode::FiducialsNode(ros::NodeHandle & nh) : it(nh)
422
449
distortionCoeffs = cv::Mat::zeros (1 , 5 , CV_64F);
423
450
424
451
haveCamInfo = false ;
452
+ enable_detections = true ;
425
453
426
454
int dicno;
427
455
@@ -506,18 +534,20 @@ FiducialsNode::FiducialsNode(ros::NodeHandle & nh) : it(nh)
506
534
507
535
image_pub = it.advertise (" /fiducial_images" , 1 );
508
536
509
-
510
537
vertices_pub = new ros::Publisher (nh.advertise <fiducial_msgs::FiducialArray>(" /fiducial_vertices" , 1 ));
511
538
512
539
pose_pub = new ros::Publisher (nh.advertise <fiducial_msgs::FiducialTransformArray>(" /fiducial_transforms" , 1 ));
513
540
514
541
dictionary = aruco::getPredefinedDictionary (dicno);
515
542
516
543
img_sub = it.subscribe (" /camera" , 1 ,
517
- &FiducialsNode::imageCallback, this );
544
+ &FiducialsNode::imageCallback, this );
518
545
519
546
caminfo_sub = nh.subscribe (" /camera_info" , 1 ,
520
- &FiducialsNode::camInfoCallback, this );
547
+ &FiducialsNode::camInfoCallback, this );
548
+
549
+ service_enable_detections = nh.advertiseService (" enable_detections" ,
550
+ &FiducialsNode::enableDetectionsCallback, this );
521
551
522
552
callbackType = boost::bind (&FiducialsNode::configCallback, this , _1, _2);
523
553
configServer.setCallback (callbackType);
0 commit comments