marker_publish.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>
45 #include <aruco_msgs/MarkerArray.h>
46 #include <tf/transform_listener.h>
47 #include <std_msgs/UInt32MultiArray.h>
48 
50 {
51 private:
52  // aruco stuff
55  vector<aruco::Marker> markers_;
56 
57  // node params
59  std::string marker_frame_;
60  std::string camera_frame_;
61  std::string reference_frame_;
62  double marker_size_;
64 
65  // ROS pub-sub
69 
75 
77  aruco_msgs::MarkerArray::Ptr marker_msg_;
78  cv::Mat inImage_;
80  std_msgs::UInt32MultiArray marker_list_msg_;
81 
82 public:
84  : nh_("~")
85  , it_(nh_)
86  , useCamInfo_(true)
87  {
88  image_sub_ = it_.subscribe("/image", 1, &ArucoMarkerPublisher::image_callback, this);
89 
90  nh_.param<bool>("use_camera_info", useCamInfo_, true);
91  if(useCamInfo_)
92  {
93  sensor_msgs::CameraInfoConstPtr msg = ros::topic::waitForMessage<sensor_msgs::CameraInfo>("/camera_info", nh_);//, 10.0);
94  camParam_ = aruco_ros::rosCameraInfo2ArucoCamParams(*msg, useRectifiedImages_);
95  nh_.param<double>("marker_size", marker_size_, 0.05);
96  nh_.param<bool>("image_is_rectified", useRectifiedImages_, true);
97  nh_.param<std::string>("reference_frame", reference_frame_, "");
98  nh_.param<std::string>("camera_frame", camera_frame_, "");
99  nh_.param<bool>("rotate_marker_axis", rotate_marker_axis_, true);
100  ROS_ASSERT(not (camera_frame_.empty() and not reference_frame_.empty()));
101  if(reference_frame_.empty())
102  reference_frame_ = camera_frame_;
103  }
104  else
105  {
106  camParam_ = aruco::CameraParameters();
107  }
108 
109  image_pub_ = it_.advertise("result", 1);
110  debug_pub_ = it_.advertise("debug", 1);
111  marker_pub_ = nh_.advertise<aruco_msgs::MarkerArray>("markers", 100);
112  marker_list_pub_ = nh_.advertise<std_msgs::UInt32MultiArray>("markers_list", 10);
113 
114  marker_msg_ = aruco_msgs::MarkerArray::Ptr(new aruco_msgs::MarkerArray());
115  marker_msg_->header.frame_id = reference_frame_;
116  marker_msg_->header.seq = 0;
117  }
118 
119  bool getTransform(const std::string& refFrame,
120  const std::string& childFrame,
121  tf::StampedTransform& transform)
122  {
123  std::string errMsg;
124 
125  if(!tfListener_.waitForTransform(refFrame,
126  childFrame,
127  ros::Time(0),
128  ros::Duration(0.5),
129  ros::Duration(0.01),
130  &errMsg))
131  {
132  ROS_ERROR_STREAM("Unable to get pose from TF: " << errMsg);
133  return false;
134  }
135  else
136  {
137  try
138  {
139  tfListener_.lookupTransform(refFrame, childFrame,
140  ros::Time(0), //get latest available
141  transform);
142  }
143  catch ( const tf::TransformException& e)
144  {
145  ROS_ERROR_STREAM("Error in lookupTransform of " << childFrame << " in " << refFrame);
146  return false;
147  }
148 
149  }
150  return true;
151  }
152 
153  void image_callback(const sensor_msgs::ImageConstPtr& msg)
154  {
155  bool publishMarkers = marker_pub_.getNumSubscribers() > 0;
156  bool publishMarkersList = marker_list_pub_.getNumSubscribers() > 0;
157  bool publishImage = image_pub_.getNumSubscribers() > 0;
158  bool publishDebug = debug_pub_.getNumSubscribers() > 0;
159 
160  if(!publishMarkers && !publishMarkersList && !publishImage && !publishDebug)
161  return;
162 
163  ros::Time curr_stamp = msg->header.stamp;
164  cv_bridge::CvImagePtr cv_ptr;
165  try
166  {
168  inImage_ = cv_ptr->image;
169 
170  //clear out previous detection results
171  markers_.clear();
172 
173  //Ok, let's detect
174  mDetector_.detect(inImage_, markers_, camParam_, marker_size_, false);
175 
176  // marker array publish
177  if(publishMarkers)
178  {
179  marker_msg_->markers.clear();
180  marker_msg_->markers.resize(markers_.size());
181  marker_msg_->header.stamp = curr_stamp;
182  marker_msg_->header.seq++;
183 
184  for(size_t i=0; i<markers_.size(); ++i)
185  {
186  aruco_msgs::Marker & marker_i = marker_msg_->markers.at(i);
187  marker_i.header.stamp = curr_stamp;
188  marker_i.id = markers_.at(i).id;
189  marker_i.confidence = 1.0;
190  }
191 
192  // if there is camera info let's do 3D stuff
193  if(useCamInfo_)
194  {
195  //get the current transform from the camera frame to output ref frame
196  tf::StampedTransform cameraToReference;
197  cameraToReference.setIdentity();
198 
199  if ( reference_frame_ != camera_frame_ )
200  {
201  getTransform(reference_frame_,
202  camera_frame_,
203  cameraToReference);
204  }
205 
206  //Now find the transform for each detected marker
207  for(size_t i=0; i<markers_.size(); ++i)
208  {
209  aruco_msgs::Marker & marker_i = marker_msg_->markers.at(i);
210  tf::Transform transform = aruco_ros::arucoMarker2Tf(markers_[i], rotate_marker_axis_);
211  transform = static_cast<tf::Transform>(cameraToReference) * transform;
212  tf::poseTFToMsg(transform, marker_i.pose.pose);
213  marker_i.header.frame_id = reference_frame_;
214  }
215  }
216 
217  //publish marker array
218  if (marker_msg_->markers.size() > 0)
219  marker_pub_.publish(marker_msg_);
220  }
221 
222  if(publishMarkersList)
223  {
224  marker_list_msg_.data.resize(markers_.size());
225  for(size_t i=0; i<markers_.size(); ++i)
226  marker_list_msg_.data[i] = markers_[i].id;
227 
228  marker_list_pub_.publish(marker_list_msg_);
229  }
230 
231  // Draw detected markers on the image for visualization
232  for(size_t i=0; i<markers_.size(); ++i)
233  {
234  markers_[i].draw(inImage_,cv::Scalar(0,0,255),2);
235  }
236 
237  //draw a 3d cube in each marker if there is 3d info
238  if(camParam_.isValid() && marker_size_>0)
239  {
240  for(size_t i=0; i<markers_.size(); ++i)
241  aruco::CvDrawingUtils::draw3dAxis(inImage_, markers_[i], camParam_);
242  }
243 
244  // publish input image with markers drawn on it
245  if(publishImage)
246  {
247  //show input with augmented information
248  cv_bridge::CvImage out_msg;
249  out_msg.header.stamp = curr_stamp;
251  out_msg.image = inImage_;
252  image_pub_.publish(out_msg.toImageMsg());
253  }
254 
255  // publish image after internal image processing
256  if(publishDebug)
257  {
258  //show also the internal image resulting from the threshold operation
259  cv_bridge::CvImage debug_msg;
260  debug_msg.header.stamp = curr_stamp;
262  debug_msg.image = mDetector_.getThresholdedImage();
263  debug_pub_.publish(debug_msg.toImageMsg());
264  }
265 
266  }
267  catch (cv_bridge::Exception& e)
268  {
269  ROS_ERROR("cv_bridge exception: %s", e.what());
270  }
271  }
272 };
273 
274 
275 int main(int argc,char **argv)
276 {
277  ros::init(argc, argv, "aruco_marker_publisher");
278 
280 
281  ros::spin();
282 }
std_msgs::UInt32MultiArray marker_list_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())
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)
ros::Publisher marker_pub_
image_transport::Publisher debug_pub_
ros::Publisher marker_list_pub_
image_transport::ImageTransport it_
void publish(const boost::shared_ptr< M > &message) const
aruco_msgs::MarkerArray::Ptr marker_msg_
tf::TransformListener tfListener_
ros::Subscriber cam_info_sub_
int main(int argc, char **argv)
std::string reference_frame_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
image_transport::Publisher image_pub_
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spin(Spinner &spinner)
void setIdentity()
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
tf::Transform arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis=true)
void publish(const sensor_msgs::Image &message) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
aruco::CameraParameters camParam_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
static void draw3dAxis(cv::Mat &Image, Marker &m, const CameraParameters &CP)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...
const cv::Mat & getThresholdedImage()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
void image_callback(const sensor_msgs::ImageConstPtr &msg)
ros::NodeHandle nh_
bool getTransform(const std::string &refFrame, const std::string &childFrame, tf::StampedTransform &transform)
uint32_t getNumSubscribers() const
image_transport::Subscriber image_sub_
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
vector< aruco::Marker > markers_
aruco::MarkerDetector mDetector_
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header header


aruco_ros
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Wed Sep 2 2020 04:02:14