-
Notifications
You must be signed in to change notification settings - Fork 302
/
simple_single.cpp
342 lines (291 loc) · 12.4 KB
/
simple_single.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
/*****************************
Copyright 2011 Rafael Muñoz Salinas. 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 Rafael Muñoz Salinas ''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 Rafael Muñoz Salinas 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 Rafael Muñoz Salinas.
********************************/
/**
* @file simple_single.cpp
* @author Bence Magyar
* @date June 2012
* @version 0.1
* @brief ROS version of the example named "simple" in the ArUco software package.
*/
#include <iostream>
#include <aruco/aruco.h>
#include <aruco/cvdrawingutils.h>
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <aruco_ros/aruco_ros_utils.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <visualization_msgs/Marker.h>
#include <dynamic_reconfigure/server.h>
#include <aruco_ros/ArucoThresholdConfig.h>
class ArucoSimple
{
private:
cv::Mat inImage;
aruco::CameraParameters camParam;
tf::StampedTransform rightToLeft;
bool useRectifiedImages;
aruco::MarkerDetector mDetector;
std::vector<aruco::Marker> markers;
ros::Subscriber cam_info_sub;
bool cam_info_received;
image_transport::Publisher image_pub;
image_transport::Publisher debug_pub;
ros::Publisher pose_pub;
ros::Publisher transform_pub;
ros::Publisher position_pub;
ros::Publisher marker_pub; // rviz visualization marker
ros::Publisher pixel_pub;
std::string marker_frame;
std::string camera_frame;
std::string reference_frame;
double marker_size;
int marker_id;
ros::NodeHandle nh;
image_transport::ImageTransport it;
image_transport::Subscriber image_sub;
tf::TransformListener _tfListener;
dynamic_reconfigure::Server<aruco_ros::ArucoThresholdConfig> dyn_rec_server;
public:
ArucoSimple() :
cam_info_received(false), nh("~"), it(nh)
{
if (nh.hasParam("corner_refinement"))
ROS_WARN(
"Corner refinement options have been removed in ArUco 3.0.0, corner_refinement ROS parameter is deprecated");
aruco::MarkerDetector::Params params = mDetector.getParameters();
std::string thresh_method;
switch (params.thresMethod)
{
case aruco::MarkerDetector::ThresMethod::THRES_ADAPTIVE:
thresh_method = "THRESH_ADAPTIVE";
break;
case aruco::MarkerDetector::ThresMethod::THRES_AUTO_FIXED:
thresh_method = "THRESH_AUTO_FIXED";
break;
default:
thresh_method = "UNKNOWN";
break;
}
// Print parameters of ArUco marker detector:
ROS_INFO_STREAM("Threshold method: " << thresh_method);
float min_marker_size; // percentage of image area
nh.param<float>("min_marker_size", min_marker_size, 0.02);
std::string detection_mode;
nh.param<std::string>("detection_mode", detection_mode, "DM_FAST");
if (detection_mode == "DM_FAST")
mDetector.setDetectionMode(aruco::DM_FAST, min_marker_size);
else if (detection_mode == "DM_VIDEO_FAST")
mDetector.setDetectionMode(aruco::DM_VIDEO_FAST, min_marker_size);
else
// Aruco version 2 mode
mDetector.setDetectionMode(aruco::DM_NORMAL, min_marker_size);
ROS_INFO_STREAM("Marker size min: " << min_marker_size << "% of image area");
ROS_INFO_STREAM("Detection mode: " << detection_mode);
image_sub = it.subscribe("/image", 1, &ArucoSimple::image_callback, this);
cam_info_sub = nh.subscribe("/camera_info", 1, &ArucoSimple::cam_info_callback, this);
image_pub = it.advertise("result", 1);
debug_pub = it.advertise("debug", 1);
pose_pub = nh.advertise<geometry_msgs::PoseStamped>("pose", 100);
transform_pub = nh.advertise<geometry_msgs::TransformStamped>("transform", 100);
position_pub = nh.advertise<geometry_msgs::Vector3Stamped>("position", 100);
marker_pub = nh.advertise<visualization_msgs::Marker>("marker", 10);
pixel_pub = nh.advertise<geometry_msgs::PointStamped>("pixel", 10);
nh.param<double>("marker_size", marker_size, 0.05);
nh.param<int>("marker_id", marker_id, 300);
nh.param<std::string>("reference_frame", reference_frame, "");
nh.param<std::string>("camera_frame", camera_frame, "");
nh.param<std::string>("marker_frame", marker_frame, "");
nh.param<bool>("image_is_rectified", useRectifiedImages, true);
ROS_ASSERT(camera_frame != "" && marker_frame != "");
if (reference_frame.empty())
reference_frame = camera_frame;
ROS_INFO("ArUco node started with marker size of %f m and marker id to track: %d", marker_size, marker_id);
ROS_INFO("ArUco node will publish pose to TF with %s as parent and %s as child.", reference_frame.c_str(),
marker_frame.c_str());
dyn_rec_server.setCallback(boost::bind(&ArucoSimple::reconf_callback, this, _1, _2));
}
bool getTransform(const std::string& refFrame, const std::string& childFrame, tf::StampedTransform& transform)
{
std::string errMsg;
if (!_tfListener.waitForTransform(refFrame, childFrame, ros::Time(0), ros::Duration(0.5), ros::Duration(0.01),
&errMsg))
{
ROS_ERROR_STREAM("Unable to get pose from TF: " << errMsg);
return false;
}
else
{
try
{
_tfListener.lookupTransform(refFrame, childFrame, ros::Time(0), // get latest available
transform);
}
catch (const tf::TransformException& e)
{
ROS_ERROR_STREAM("Error in lookupTransform of " << childFrame << " in " << refFrame);
return false;
}
}
return true;
}
void image_callback(const sensor_msgs::ImageConstPtr& msg)
{
if ((image_pub.getNumSubscribers() == 0) && (debug_pub.getNumSubscribers() == 0)
&& (pose_pub.getNumSubscribers() == 0) && (transform_pub.getNumSubscribers() == 0)
&& (position_pub.getNumSubscribers() == 0) && (marker_pub.getNumSubscribers() == 0)
&& (pixel_pub.getNumSubscribers() == 0))
{
ROS_DEBUG("No subscribers, not looking for ArUco markers");
return;
}
static tf::TransformBroadcaster br;
if (cam_info_received)
{
ros::Time curr_stamp = msg->header.stamp;
cv_bridge::CvImagePtr cv_ptr;
try
{
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::RGB8);
inImage = cv_ptr->image;
// detection results will go into "markers"
markers.clear();
// ok, let's detect
mDetector.detect(inImage, markers, camParam, marker_size, false);
// for each marker, draw info and its boundaries in the image
for (std::size_t i = 0; i < markers.size(); ++i)
{
// only publishing the selected marker
if (markers[i].id == marker_id)
{
tf::Transform transform = aruco_ros::arucoMarker2Tf(markers[i]);
tf::StampedTransform cameraToReference;
cameraToReference.setIdentity();
if (reference_frame != camera_frame)
{
getTransform(reference_frame, camera_frame, cameraToReference);
}
transform = static_cast<tf::Transform>(cameraToReference) * static_cast<tf::Transform>(rightToLeft)
* transform;
tf::StampedTransform stampedTransform(transform, curr_stamp, reference_frame, marker_frame);
br.sendTransform(stampedTransform);
geometry_msgs::PoseStamped poseMsg;
tf::poseTFToMsg(transform, poseMsg.pose);
poseMsg.header.frame_id = reference_frame;
poseMsg.header.stamp = curr_stamp;
pose_pub.publish(poseMsg);
geometry_msgs::TransformStamped transformMsg;
tf::transformStampedTFToMsg(stampedTransform, transformMsg);
transform_pub.publish(transformMsg);
geometry_msgs::Vector3Stamped positionMsg;
positionMsg.header = transformMsg.header;
positionMsg.vector = transformMsg.transform.translation;
position_pub.publish(positionMsg);
geometry_msgs::PointStamped pixelMsg;
pixelMsg.header = transformMsg.header;
pixelMsg.point.x = markers[i].getCenter().x;
pixelMsg.point.y = markers[i].getCenter().y;
pixelMsg.point.z = 0;
pixel_pub.publish(pixelMsg);
// publish rviz marker representing the ArUco marker patch
visualization_msgs::Marker visMarker;
visMarker.header = transformMsg.header;
visMarker.id = 1;
visMarker.type = visualization_msgs::Marker::CUBE;
visMarker.action = visualization_msgs::Marker::ADD;
visMarker.pose = poseMsg.pose;
visMarker.scale.x = marker_size;
visMarker.scale.y = marker_size;
visMarker.scale.z = 0.001;
visMarker.color.r = 1.0;
visMarker.color.g = 0;
visMarker.color.b = 0;
visMarker.color.a = 1.0;
visMarker.lifetime = ros::Duration(3.0);
marker_pub.publish(visMarker);
}
// but drawing all the detected markers
markers[i].draw(inImage, cv::Scalar(0, 0, 255), 2);
}
// draw a 3d cube in each marker if there is 3d info
if (camParam.isValid() && marker_size != -1)
{
for (std::size_t i = 0; i < markers.size(); ++i)
{
aruco::CvDrawingUtils::draw3dAxis(inImage, markers[i], camParam);
}
}
if (image_pub.getNumSubscribers() > 0)
{
// show input with augmented information
cv_bridge::CvImage out_msg;
out_msg.header.stamp = curr_stamp;
out_msg.encoding = sensor_msgs::image_encodings::RGB8;
out_msg.image = inImage;
image_pub.publish(out_msg.toImageMsg());
}
if (debug_pub.getNumSubscribers() > 0)
{
// show also the internal image resulting from the threshold operation
cv_bridge::CvImage debug_msg;
debug_msg.header.stamp = curr_stamp;
debug_msg.encoding = sensor_msgs::image_encodings::MONO8;
debug_msg.image = mDetector.getThresholdedImage();
debug_pub.publish(debug_msg.toImageMsg());
}
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
}
}
// wait for one camerainfo, then shut down that subscriber
void cam_info_callback(const sensor_msgs::CameraInfo &msg)
{
camParam = aruco_ros::rosCameraInfo2ArucoCamParams(msg, useRectifiedImages);
// handle cartesian offset between stereo pairs
// see the sensor_msgs/CameraInfo documentation for details
rightToLeft.setIdentity();
rightToLeft.setOrigin(tf::Vector3(-msg.P[3] / msg.P[0], -msg.P[7] / msg.P[5], 0.0));
cam_info_received = true;
cam_info_sub.shutdown();
}
void reconf_callback(aruco_ros::ArucoThresholdConfig &config, uint32_t level)
{
mDetector.setDetectionMode(aruco::DetectionMode(config.detection_mode), config.min_image_size);
if (config.normalizeImage)
{
ROS_WARN("normalizeImageIllumination is unimplemented!");
}
}
};
int main(int argc, char **argv)
{
ros::init(argc, argv, "aruco_simple");
ArucoSimple node;
ros::spin();
}