simple_single.cpp
Go to the documentation of this file.
1 /*****************************
2  Copyright 2011 Rafael Muñoz Salinas. All rights reserved.
3 
4  Redistribution and use in source and binary forms, with or without modification, are
5  permitted provided that the following conditions are met:
6 
7  1. Redistributions of source code must retain the above copyright notice, this list of
8  conditions and the following disclaimer.
9 
10  2. Redistributions in binary form must reproduce the above copyright notice, this list
11  of conditions and the following disclaimer in the documentation and/or other materials
12  provided with the distribution.
13 
14  THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED
15  WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
16  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR
17  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
18  CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
19  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
20  ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
21  NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
22  ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23 
24  The views and conclusions contained in the software and documentation are those of the
25  authors and should not be interpreted as representing official policies, either expressed
26  or implied, of Rafael Muñoz Salinas.
27  ********************************/
36 #include <iostream>
37 #include <aruco/aruco.h>
38 #include <aruco/cvdrawingutils.h>
39 
40 #include <ros/ros.h>
42 #include <cv_bridge/cv_bridge.h>
46 #include <tf/transform_listener.h>
47 #include <visualization_msgs/Marker.h>
48 
49 #include <dynamic_reconfigure/server.h>
50 #include <aruco_ros/ArucoThresholdConfig.h>
51 
53 {
54 private:
55  cv::Mat inImage;
60  std::vector<aruco::Marker> markers;
68  ros::Publisher marker_pub; // rviz visualization marker
70  std::string marker_frame;
71  std::string camera_frame;
72  std::string reference_frame;
73 
74  double marker_size;
75  int marker_id;
76 
80 
82 
83  dynamic_reconfigure::Server<aruco_ros::ArucoThresholdConfig> dyn_rec_server;
84 
85 public:
87  cam_info_received(false), nh("~"), it(nh)
88  {
89 
90  if (nh.hasParam("corner_refinement"))
91  ROS_WARN(
92  "Corner refinement options have been removed in ArUco 3.0.0, corner_refinement ROS parameter is deprecated");
93 
95  std::string thresh_method;
96  switch (params.thresMethod)
97  {
98  case aruco::MarkerDetector::ThresMethod::THRES_ADAPTIVE:
99  thresh_method = "THRESH_ADAPTIVE";
100  break;
101  case aruco::MarkerDetector::ThresMethod::THRES_AUTO_FIXED:
102  thresh_method = "THRESH_AUTO_FIXED";
103  break;
104  default:
105  thresh_method = "UNKNOWN";
106  break;
107  }
108 
109  // Print parameters of ArUco marker detector:
110  ROS_INFO_STREAM("Threshold method: " << thresh_method);
111 
112  float min_marker_size; // percentage of image area
113  nh.param<float>("min_marker_size", min_marker_size, 0.02);
114 
115  std::string detection_mode;
116  nh.param<std::string>("detection_mode", detection_mode, "DM_FAST");
117  if (detection_mode == "DM_FAST")
118  mDetector.setDetectionMode(aruco::DM_FAST, min_marker_size);
119  else if (detection_mode == "DM_VIDEO_FAST")
121  else
122  // Aruco version 2 mode
123  mDetector.setDetectionMode(aruco::DM_NORMAL, min_marker_size);
124 
125  ROS_INFO_STREAM("Marker size min: " << min_marker_size << "% of image area");
126  ROS_INFO_STREAM("Detection mode: " << detection_mode);
127 
128  image_sub = it.subscribe("/image", 1, &ArucoSimple::image_callback, this);
129  cam_info_sub = nh.subscribe("/camera_info", 1, &ArucoSimple::cam_info_callback, this);
130 
131  image_pub = it.advertise("result", 1);
132  debug_pub = it.advertise("debug", 1);
133  pose_pub = nh.advertise<geometry_msgs::PoseStamped>("pose", 100);
134  transform_pub = nh.advertise<geometry_msgs::TransformStamped>("transform", 100);
135  position_pub = nh.advertise<geometry_msgs::Vector3Stamped>("position", 100);
136  marker_pub = nh.advertise<visualization_msgs::Marker>("marker", 10);
137  pixel_pub = nh.advertise<geometry_msgs::PointStamped>("pixel", 10);
138 
139  nh.param<double>("marker_size", marker_size, 0.05);
140  nh.param<int>("marker_id", marker_id, 300);
141  nh.param<std::string>("reference_frame", reference_frame, "");
142  nh.param<std::string>("camera_frame", camera_frame, "");
143  nh.param<std::string>("marker_frame", marker_frame, "");
144  nh.param<bool>("image_is_rectified", useRectifiedImages, true);
145 
146  ROS_ASSERT(camera_frame != "" && marker_frame != "");
147 
148  if (reference_frame.empty())
150 
151  ROS_INFO("ArUco node started with marker size of %f m and marker id to track: %d", marker_size, marker_id);
152  ROS_INFO("ArUco node will publish pose to TF with %s as parent and %s as child.", reference_frame.c_str(),
153  marker_frame.c_str());
154 
155  dyn_rec_server.setCallback(boost::bind(&ArucoSimple::reconf_callback, this, _1, _2));
156  }
157 
158  bool getTransform(const std::string& refFrame, const std::string& childFrame, tf::StampedTransform& transform)
159  {
160  std::string errMsg;
161 
162  if (!_tfListener.waitForTransform(refFrame, childFrame, ros::Time(0), ros::Duration(0.5), ros::Duration(0.01),
163  &errMsg))
164  {
165  ROS_ERROR_STREAM("Unable to get pose from TF: " << errMsg);
166  return false;
167  }
168  else
169  {
170  try
171  {
172  _tfListener.lookupTransform(refFrame, childFrame, ros::Time(0), // get latest available
173  transform);
174  }
175  catch (const tf::TransformException& e)
176  {
177  ROS_ERROR_STREAM("Error in lookupTransform of " << childFrame << " in " << refFrame);
178  return false;
179  }
180 
181  }
182  return true;
183  }
184 
185  void image_callback(const sensor_msgs::ImageConstPtr& msg)
186  {
187  if ((image_pub.getNumSubscribers() == 0) && (debug_pub.getNumSubscribers() == 0)
190  && (pixel_pub.getNumSubscribers() == 0))
191  {
192  ROS_DEBUG("No subscribers, not looking for ArUco markers");
193  return;
194  }
195 
196  static tf::TransformBroadcaster br;
197  if (cam_info_received)
198  {
199  ros::Time curr_stamp = msg->header.stamp;
200  cv_bridge::CvImagePtr cv_ptr;
201  try
202  {
204  inImage = cv_ptr->image;
205 
206  // detection results will go into "markers"
207  markers.clear();
208  // ok, let's detect
210  // for each marker, draw info and its boundaries in the image
211  for (std::size_t i = 0; i < markers.size(); ++i)
212  {
213  // only publishing the selected marker
214  if (markers[i].id == marker_id)
215  {
217  tf::StampedTransform cameraToReference;
218  cameraToReference.setIdentity();
219 
221  {
222  getTransform(reference_frame, camera_frame, cameraToReference);
223  }
224 
225  transform = static_cast<tf::Transform>(cameraToReference) * static_cast<tf::Transform>(rightToLeft)
226  * transform;
227 
228  tf::StampedTransform stampedTransform(transform, curr_stamp, reference_frame, marker_frame);
229  br.sendTransform(stampedTransform);
230  geometry_msgs::PoseStamped poseMsg;
231  tf::poseTFToMsg(transform, poseMsg.pose);
232  poseMsg.header.frame_id = reference_frame;
233  poseMsg.header.stamp = curr_stamp;
234  pose_pub.publish(poseMsg);
235 
236  geometry_msgs::TransformStamped transformMsg;
237  tf::transformStampedTFToMsg(stampedTransform, transformMsg);
238  transform_pub.publish(transformMsg);
239 
240  geometry_msgs::Vector3Stamped positionMsg;
241  positionMsg.header = transformMsg.header;
242  positionMsg.vector = transformMsg.transform.translation;
243  position_pub.publish(positionMsg);
244 
245  geometry_msgs::PointStamped pixelMsg;
246  pixelMsg.header = transformMsg.header;
247  pixelMsg.point.x = markers[i].getCenter().x;
248  pixelMsg.point.y = markers[i].getCenter().y;
249  pixelMsg.point.z = 0;
250  pixel_pub.publish(pixelMsg);
251 
252  // publish rviz marker representing the ArUco marker patch
253  visualization_msgs::Marker visMarker;
254  visMarker.header = transformMsg.header;
255  visMarker.id = 1;
256  visMarker.type = visualization_msgs::Marker::CUBE;
257  visMarker.action = visualization_msgs::Marker::ADD;
258  visMarker.pose = poseMsg.pose;
259  visMarker.scale.x = marker_size;
260  visMarker.scale.y = marker_size;
261  visMarker.scale.z = 0.001;
262  visMarker.color.r = 1.0;
263  visMarker.color.g = 0;
264  visMarker.color.b = 0;
265  visMarker.color.a = 1.0;
266  visMarker.lifetime = ros::Duration(3.0);
267  marker_pub.publish(visMarker);
268 
269  }
270  // but drawing all the detected markers
271  markers[i].draw(inImage, cv::Scalar(0, 0, 255), 2);
272  }
273 
274  // draw a 3d cube in each marker if there is 3d info
275  if (camParam.isValid() && marker_size != -1)
276  {
277  for (std::size_t i = 0; i < markers.size(); ++i)
278  {
280  }
281  }
282 
283  if (image_pub.getNumSubscribers() > 0)
284  {
285  // show input with augmented information
286  cv_bridge::CvImage out_msg;
287  out_msg.header.stamp = curr_stamp;
289  out_msg.image = inImage;
290  image_pub.publish(out_msg.toImageMsg());
291  }
292 
293  if (debug_pub.getNumSubscribers() > 0)
294  {
295  // show also the internal image resulting from the threshold operation
296  cv_bridge::CvImage debug_msg;
297  debug_msg.header.stamp = curr_stamp;
299  debug_msg.image = mDetector.getThresholdedImage();
300  debug_pub.publish(debug_msg.toImageMsg());
301  }
302  }
303  catch (cv_bridge::Exception& e)
304  {
305  ROS_ERROR("cv_bridge exception: %s", e.what());
306  return;
307  }
308  }
309  }
310 
311  // wait for one camerainfo, then shut down that subscriber
312  void cam_info_callback(const sensor_msgs::CameraInfo &msg)
313  {
315 
316  // handle cartesian offset between stereo pairs
317  // see the sensor_msgs/CameraInfo documentation for details
319  rightToLeft.setOrigin(tf::Vector3(-msg.P[3] / msg.P[0], -msg.P[7] / msg.P[5], 0.0));
320 
321  cam_info_received = true;
323  }
324 
325  void reconf_callback(aruco_ros::ArucoThresholdConfig &config, uint32_t level)
326  {
327  mDetector.setDetectionMode(aruco::DetectionMode(config.detection_mode), config.min_image_size);
328  if (config.normalizeImage)
329  {
330  ROS_WARN("normalizeImageIllumination is unimplemented!");
331  }
332  }
333 };
334 
335 int main(int argc, char **argv)
336 {
337  ros::init(argc, argv, "aruco_simple");
338 
339  ArucoSimple node;
340 
341  ros::spin();
342 }
cvdrawingutils.h
aruco::DM_FAST
DM_FAST
ArucoSimple::marker_frame
std::string marker_frame
Definition: simple_single.cpp:70
aruco_ros_utils.h
aruco::DM_VIDEO_FAST
DM_VIDEO_FAST
ros::Publisher
aruco::MarkerDetector::getParameters
Params & getParameters()
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
image_encodings.h
aruco.h
image_transport::ImageTransport
ArucoSimple::useRectifiedImages
bool useRectifiedImages
Definition: simple_single.cpp:58
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
ArucoSimple::cam_info_sub
ros::Subscriber cam_info_sub
Definition: simple_single.cpp:61
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
ArucoSimple::ArucoSimple
ArucoSimple()
Definition: simple_single.cpp:86
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
aruco::CameraParameters
ArucoSimple::it
image_transport::ImageTransport it
Definition: simple_single.cpp:78
ArucoSimple::marker_size
double marker_size
Definition: simple_single.cpp:74
ros.h
ArucoSimple::pose_pub
ros::Publisher pose_pub
Definition: simple_single.cpp:65
aruco::MarkerDetector::Params::thresMethod
ThresMethod thresMethod
image_transport::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
ArucoSimple::reconf_callback
void reconf_callback(aruco_ros::ArucoThresholdConfig &config, uint32_t level)
Definition: simple_single.cpp:325
aruco::MarkerDetector::setDetectionMode
void setDetectionMode(DetectionMode dm, float minMarkerSize=0)
tf::poseTFToMsg
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
ros::Subscriber::shutdown
void shutdown()
ArucoSimple::nh
ros::NodeHandle nh
Definition: simple_single.cpp:77
aruco::CvDrawingUtils::draw3dAxis
static void draw3dAxis(cv::Mat &Image, const CameraParameters &CP, const cv::Mat &Rvec, const cv::Mat &Tvec, float axis_size)
aruco::CameraParameters::isValid
bool isValid() const
ArucoSimple::inImage
cv::Mat inImage
Definition: simple_single.cpp:55
cv_bridge::Exception
sensor_msgs::image_encodings::RGB8
const std::string RGB8
tf::StampedTransform
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
transform_broadcaster.h
aruco::MarkerDetector::detect
std::vector< aruco::Marker > detect(const cv::Mat &input)
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Subscriber
ArucoSimple::marker_pub
ros::Publisher marker_pub
Definition: simple_single.cpp:68
ArucoSimple::pixel_pub
ros::Publisher pixel_pub
Definition: simple_single.cpp:69
ArucoSimple::markers
std::vector< aruco::Marker > markers
Definition: simple_single.cpp:60
ArucoSimple::image_pub
image_transport::Publisher image_pub
Definition: simple_single.cpp:63
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
cv_bridge::CvImage::header
std_msgs::Header header
ROS_DEBUG
#define ROS_DEBUG(...)
image_transport::ImageTransport::subscribe
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())
tf::TransformBroadcaster
ArucoSimple::transform_pub
ros::Publisher transform_pub
Definition: simple_single.cpp:66
ArucoSimple::image_callback
void image_callback(const sensor_msgs::ImageConstPtr &msg)
Definition: simple_single.cpp:185
ArucoSimple::position_pub
ros::Publisher position_pub
Definition: simple_single.cpp:67
ArucoSimple::marker_id
int marker_id
Definition: simple_single.cpp:75
ArucoSimple::camParam
aruco::CameraParameters camParam
Definition: simple_single.cpp:56
aruco_ros::rosCameraInfo2ArucoCamParams
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...
Definition: aruco_ros_utils.cpp:9
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
aruco::DM_NORMAL
DM_NORMAL
ROS_WARN
#define ROS_WARN(...)
main
int main(int argc, char **argv)
Definition: simple_single.cpp:335
aruco_ros::arucoMarker2Tf
tf::Transform arucoMarker2Tf(const aruco::Marker &marker)
Definition: aruco_ros_utils.cpp:59
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf::Transformer::waitForTransform
bool waitForTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
tf::Transform
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
tf::Transform::setOrigin
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
ArucoSimple::image_sub
image_transport::Subscriber image_sub
Definition: simple_single.cpp:79
tf::transformStampedTFToMsg
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
ArucoSimple::cam_info_callback
void cam_info_callback(const sensor_msgs::CameraInfo &msg)
Definition: simple_single.cpp:312
ArucoSimple::reference_frame
std::string reference_frame
Definition: simple_single.cpp:72
image_transport.h
transform_listener.h
aruco::MarkerDetector::Params
ArucoSimple::_tfListener
tf::TransformListener _tfListener
Definition: simple_single.cpp:81
ArucoSimple::debug_pub
image_transport::Publisher debug_pub
Definition: simple_single.cpp:64
ros::Time
cv_bridge::CvImage::encoding
std::string encoding
ArucoSimple::mDetector
aruco::MarkerDetector mDetector
Definition: simple_single.cpp:59
ArucoSimple::camera_frame
std::string camera_frame
Definition: simple_single.cpp:71
image_transport::Publisher
sensor_msgs::image_encodings::MONO8
const std::string MONO8
aruco::MarkerDetector
cv_bridge.h
ROS_ERROR
#define ROS_ERROR(...)
cv_bridge::CvImage
tf::TransformListener
tf::Transform::setIdentity
void setIdentity()
aruco::DetectionMode
DetectionMode
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
ArucoSimple::getTransform
bool getTransform(const std::string &refFrame, const std::string &childFrame, tf::StampedTransform &transform)
Definition: simple_single.cpp:158
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
ArucoSimple
Definition: simple_single.cpp:52
ArucoSimple::cam_info_received
bool cam_info_received
Definition: simple_single.cpp:62
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
ArucoSimple::rightToLeft
tf::StampedTransform rightToLeft
Definition: simple_single.cpp:57
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
ROS_ASSERT
#define ROS_ASSERT(cond)
cv_bridge::CvImage::image
cv::Mat image
ros::Duration
ros::NodeHandle
aruco::MarkerDetector::getThresholdedImage
cv::Mat getThresholdedImage(uint32_t idx=0)
ros::Subscriber
ArucoSimple::dyn_rec_server
dynamic_reconfigure::Server< aruco_ros::ArucoThresholdConfig > dyn_rec_server
Definition: simple_single.cpp:83


aruco_ros
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Sat Sep 23 2023 02:26:51