old/aruco_ros/src/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 <opencv2/core/core.hpp>
41 #include <ros/ros.h>
43 #include <cv_bridge/cv_bridge.h>
45 #include <aruco_ros/aruco_ros_utils.h>
47 #include <tf/transform_listener.h>
48 #include <visualization_msgs/Marker.h>
49 
50 using namespace aruco;
51 
52 class ArucoSimple
53 {
54 private:
55  cv::Mat inImage;
57  tf::StampedTransform rightToLeft;
58  bool useRectifiedImages;
60  vector<Marker> markers;
62  bool cam_info_received;
65  ros::Publisher pose_pub;
66  ros::Publisher transform_pub;
67  ros::Publisher position_pub;
68  ros::Publisher marker_pub; //rviz visualization marker
69  ros::Publisher pixel_pub;
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 
77  ros::NodeHandle nh;
80 
81  tf::TransformListener _tfListener;
82 
83 public:
85  : cam_info_received(false),
86  nh("~"),
87  it(nh)
88  {
89 
90  std::string refinementMethod;
91  nh.param<std::string>("corner_refinement", refinementMethod, "LINES");
92  if ( refinementMethod == "SUBPIX" )
94  else if ( refinementMethod == "HARRIS" )
96  else if ( refinementMethod == "NONE" )
98  else
100 
101  //Print parameters of aruco marker detector:
102  ROS_INFO_STREAM("Corner refinement method: " << mDetector.getCornerRefinementMethod());
103  ROS_INFO_STREAM("Threshold method: " << mDetector.getThresholdMethod());
104  double th1, th2;
105  mDetector.getThresholdParams(th1, th2);
106  ROS_INFO_STREAM("Threshold method: " << " th1: " << th1 << " th2: " << th2);
107  float mins, maxs;
108  mDetector.getMinMaxSize(mins, maxs);
109  ROS_INFO_STREAM("Marker size min: " << mins << " max: " << maxs);
110  ROS_INFO_STREAM("Desired speed: " << mDetector.getDesiredSpeed());
111 
112 
113 
114  image_sub = it.subscribe("/image", 1, &ArucoSimple::image_callback, this);
115  cam_info_sub = nh.subscribe("/camera_info", 1, &ArucoSimple::cam_info_callback, this);
116 
117  image_pub = it.advertise("result", 1);
118  debug_pub = it.advertise("debug", 1);
119  pose_pub = nh.advertise<geometry_msgs::PoseStamped>("pose", 100);
120  transform_pub = nh.advertise<geometry_msgs::TransformStamped>("transform", 100);
121  position_pub = nh.advertise<geometry_msgs::Vector3Stamped>("position", 100);
122  marker_pub = nh.advertise<visualization_msgs::Marker>("marker", 10);
123  pixel_pub = nh.advertise<geometry_msgs::PointStamped>("pixel", 10);
124 
125  nh.param<double>("marker_size", marker_size, 0.05);
126  nh.param<int>("marker_id", marker_id, 300);
127  nh.param<std::string>("reference_frame", reference_frame, "");
128  nh.param<std::string>("camera_frame", camera_frame, "");
129  nh.param<std::string>("marker_frame", marker_frame, "");
130  nh.param<bool>("image_is_rectified", useRectifiedImages, true);
131 
132  ROS_ASSERT(camera_frame != "" && marker_frame != "");
133 
134  if ( reference_frame.empty() )
135  reference_frame = camera_frame;
136 
137  ROS_INFO("Aruco node started with marker size of %f m and marker id to track: %d",
138  marker_size, marker_id);
139  ROS_INFO("Aruco node will publish pose to TF with %s as parent and %s as child.",
140  reference_frame.c_str(), marker_frame.c_str());
141  }
142 
143  bool getTransform(const std::string& refFrame,
144  const std::string& childFrame,
146  {
147  std::string errMsg;
148 
149  if ( !_tfListener.waitForTransform(refFrame,
150  childFrame,
151  ros::Time(0),
152  ros::Duration(0.5),
153  ros::Duration(0.01),
154  &errMsg)
155  )
156  {
157  ROS_ERROR_STREAM("Unable to get pose from TF: " << errMsg);
158  return false;
159  }
160  else
161  {
162  try
163  {
164  _tfListener.lookupTransform( refFrame, childFrame,
165  ros::Time(0), //get latest available
166  transform);
167  }
168  catch ( const tf::TransformException& e)
169  {
170  ROS_ERROR_STREAM("Error in lookupTransform of " << childFrame << " in " << refFrame);
171  return false;
172  }
173 
174  }
175  return true;
176  }
177 
178 
179  void image_callback(const sensor_msgs::ImageConstPtr& msg)
180  {
181  static tf::TransformBroadcaster br;
182  if(cam_info_received)
183  {
184  ros::Time curr_stamp(ros::Time::now());
185  cv_bridge::CvImagePtr cv_ptr;
186  try
187  {
189  inImage = cv_ptr->image;
190 
191  //detection results will go into "markers"
192  markers.clear();
193  //Ok, let's detect
194  mDetector.detect(inImage, markers, camParam, marker_size, false);
195  //for each marker, draw info and its boundaries in the image
196  for(size_t i=0; i<markers.size(); ++i)
197  {
198  // only publishing the selected marker
199  if(markers[i].id == marker_id)
200  {
202  tf::StampedTransform cameraToReference;
203  cameraToReference.setIdentity();
204 
205  if ( reference_frame != camera_frame )
206  {
207  getTransform(reference_frame,
208  camera_frame,
209  cameraToReference);
210  }
211 
212  transform =
213  static_cast<tf::Transform>(cameraToReference)
214  * static_cast<tf::Transform>(rightToLeft)
215  * transform;
216 
217  tf::StampedTransform stampedTransform(transform, curr_stamp,
218  reference_frame, marker_frame);
219  br.sendTransform(stampedTransform);
220  geometry_msgs::PoseStamped poseMsg;
221  tf::poseTFToMsg(transform, poseMsg.pose);
222  poseMsg.header.frame_id = reference_frame;
223  poseMsg.header.stamp = curr_stamp;
224  pose_pub.publish(poseMsg);
225 
226  geometry_msgs::TransformStamped transformMsg;
227  tf::transformStampedTFToMsg(stampedTransform, transformMsg);
228  transform_pub.publish(transformMsg);
229 
230  geometry_msgs::Vector3Stamped positionMsg;
231  positionMsg.header = transformMsg.header;
232  positionMsg.vector = transformMsg.transform.translation;
233  position_pub.publish(positionMsg);
234 
235  geometry_msgs::PointStamped pixelMsg;
236  pixelMsg.header = transformMsg.header;
237  pixelMsg.point.x = markers[i].getCenter().x;
238  pixelMsg.point.y = markers[i].getCenter().y;
239  pixelMsg.point.z = 0;
240  pixel_pub.publish(pixelMsg);
241 
242  //Publish rviz marker representing the ArUco marker patch
243  visualization_msgs::Marker visMarker;
244  visMarker.header = transformMsg.header;
245  visMarker.pose = poseMsg.pose;
246  visMarker.id = 1;
247  visMarker.type = visualization_msgs::Marker::CUBE;
248  visMarker.action = visualization_msgs::Marker::ADD;
249  visMarker.pose = poseMsg.pose;
250  visMarker.scale.x = marker_size;
251  visMarker.scale.y = 0.001;
252  visMarker.scale.z = marker_size;
253  visMarker.color.r = 1.0;
254  visMarker.color.g = 0;
255  visMarker.color.b = 0;
256  visMarker.color.a = 1.0;
257  visMarker.lifetime = ros::Duration(3.0);
258  marker_pub.publish(visMarker);
259 
260  }
261  // but drawing all the detected markers
262  markers[i].draw(inImage,cv::Scalar(0,0,255),2);
263  }
264 
265  //draw a 3d cube in each marker if there is 3d info
266  if(camParam.isValid() && marker_size!=-1)
267  {
268  for(size_t i=0; i<markers.size(); ++i)
269  {
270  CvDrawingUtils::draw3dAxis(inImage, markers[i], camParam);
271  }
272  }
273 
274  if(image_pub.getNumSubscribers() > 0)
275  {
276  //show input with augmented information
277  cv_bridge::CvImage out_msg;
278  out_msg.header.stamp = curr_stamp;
280  out_msg.image = inImage;
281  image_pub.publish(out_msg.toImageMsg());
282  }
283 
284  if(debug_pub.getNumSubscribers() > 0)
285  {
286  //show also the internal image resulting from the threshold operation
287  cv_bridge::CvImage debug_msg;
288  debug_msg.header.stamp = curr_stamp;
290  debug_msg.image = mDetector.getThresholdedImage();
291  debug_pub.publish(debug_msg.toImageMsg());
292  }
293  }
294  catch (cv_bridge::Exception& e)
295  {
296  ROS_ERROR("cv_bridge exception: %s", e.what());
297  return;
298  }
299  }
300  }
301 
302  // wait for one camerainfo, then shut down that subscriber
303  void cam_info_callback(const sensor_msgs::CameraInfo &msg)
304  {
305  camParam = aruco_ros::rosCameraInfo2ArucoCamParams(msg, useRectifiedImages);
306 
307  // handle cartesian offset between stereo pairs
308  // see the sensor_msgs/CamaraInfo documentation for details
309  rightToLeft.setIdentity();
310  rightToLeft.setOrigin(
311  tf::Vector3(
312  -msg.P[3]/msg.P[0],
313  -msg.P[7]/msg.P[5],
314  0.0));
315 
316  cam_info_received = true;
317  cam_info_sub.shutdown();
318  }
319 };
320 
321 
322 int main(int argc,char **argv)
323 {
324  ros::init(argc, argv, "aruco_simple");
325 
326  ArucoSimple node;
327 
328  ros::spin();
329 }
double marker_size
bool getTransform(const std::string &refFrame, const std::string &childFrame, tf::StampedTransform &transform)
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())
void detect(const cv::Mat &input, std::vector< Marker > &detectedMarkers, cv::Mat camMatrix=cv::Mat(), cv::Mat distCoeff=cv::Mat(), float markerSizeMeters=-1, bool setYPerpendicular=true)
void getMinMaxSize(float &min, float &max)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getThresholdParams(double &param1, double &param2) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
CornerRefinementMethod getCornerRefinementMethod() const
void image_callback(const sensor_msgs::ImageConstPtr &msg)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spin(Spinner &spinner)
void setIdentity()
pcl::PointCloud< myPointXYZRID > transform(pcl::PointCloud< myPointXYZRID > pc, float x, float y, float z, float rot_x, float rot_y, float rot_z)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
ros::Subscriber cam_info_sub
int main(int argc, char **argv)
tf::Transform arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis=true)
MarkerDetector mDetector
void publish(const sensor_msgs::Image &message) const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
image_transport::Publisher image_pub
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void sendTransform(const StampedTransform &transform)
image_transport::Publisher debug_pub
bool useRectifiedImages
static void draw3dAxis(cv::Mat &Image, Marker &m, const CameraParameters &CP)
ThresholdMethods getThresholdMethod() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Main class for marker detection.
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
vector< Marker > markers
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
#define ROS_INFO_STREAM(args)
void cam_info_callback(const sensor_msgs::CameraInfo &msg)
static Time now()
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
bool cam_info_received
void setCornerRefinementMethod(CornerRefinementMethod method)
#define ROS_ERROR(...)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
sensor_msgs::ImagePtr toImageMsg() const
aruco::CameraParameters camParam
std_msgs::Header header


lidar_camera_calibration
Author(s):
autogenerated on Sat Feb 6 2021 03:39:37