old/aruco_ros/src/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 <opencv2/core/core.hpp>
41 #include <ros/ros.h>
43 #include <cv_bridge/cv_bridge.h>
45 #include <aruco_ros/aruco_ros_utils.h>
46 #include <aruco_msgs/MarkerArray.h>
47 #include <tf/transform_listener.h>
48 #include <std_msgs/UInt32MultiArray.h>
49 
51 {
52 private:
53  // aruco stuff
56  vector<aruco::Marker> markers_;
57 
58  // node params
60  std::string marker_frame_;
61  std::string camera_frame_;
62  std::string reference_frame_;
63  double marker_size_;
64 
65  // ROS pub-sub
69 
75 
77  aruco_msgs::MarkerArray::Ptr marker_msg_;
78  cv::Mat inImage_;
79  bool useCamInfo_;
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  ROS_ASSERT(not camera_frame_.empty());
100  if(reference_frame_.empty())
101  reference_frame_ = camera_frame_;
102  }
103  else
104  {
105  camParam_ = aruco::CameraParameters();
106  }
107 
108  image_pub_ = it_.advertise("result", 1);
109  debug_pub_ = it_.advertise("debug", 1);
110  marker_pub_ = nh_.advertise<aruco_msgs::MarkerArray>("markers", 100);
111  marker_list_pub_ = nh_.advertise<std_msgs::UInt32MultiArray>("markers_list", 10);
112 
113  marker_msg_ = aruco_msgs::MarkerArray::Ptr(new aruco_msgs::MarkerArray());
114  marker_msg_->header.frame_id = reference_frame_;
115  marker_msg_->header.seq = 0;
116  }
117 
118  bool getTransform(const std::string& refFrame,
119  const std::string& childFrame,
121  {
122  std::string errMsg;
123 
124  if(!tfListener_.waitForTransform(refFrame,
125  childFrame,
126  ros::Time(0),
127  ros::Duration(0.5),
128  ros::Duration(0.01),
129  &errMsg))
130  {
131  ROS_ERROR_STREAM("Unable to get pose from TF: " << errMsg);
132  return false;
133  }
134  else
135  {
136  try
137  {
138  tfListener_.lookupTransform(refFrame, childFrame,
139  ros::Time(0), //get latest available
140  transform);
141  }
142  catch ( const tf::TransformException& e)
143  {
144  ROS_ERROR_STREAM("Error in lookupTransform of " << childFrame << " in " << refFrame);
145  return false;
146  }
147 
148  }
149  return true;
150  }
151 
152  void image_callback(const sensor_msgs::ImageConstPtr& msg)
153  {
154  bool publishMarkers = marker_pub_.getNumSubscribers() > 0;
155  bool publishMarkersList = marker_list_pub_.getNumSubscribers() > 0;
156  bool publishImage = image_pub_.getNumSubscribers() > 0;
157  bool publishDebug = debug_pub_.getNumSubscribers() > 0;
158 
159  if(!publishMarkers && !publishMarkersList && !publishImage && !publishDebug)
160  return;
161 
162  ros::Time curr_stamp(ros::Time::now());
163  cv_bridge::CvImagePtr cv_ptr;
164  try
165  {
167  inImage_ = cv_ptr->image;
168 
169  //clear out previous detection results
170  markers_.clear();
171 
172  //Ok, let's detect
173  mDetector_.detect(inImage_, markers_, camParam_, marker_size_, false);
174 
175  // marker array publish
176  if(publishMarkers)
177  {
178  marker_msg_->markers.clear();
179  marker_msg_->markers.resize(markers_.size());
180  marker_msg_->header.stamp = curr_stamp;
181  marker_msg_->header.seq++;
182 
183  for(size_t i=0; i<markers_.size(); ++i)
184  {
185  aruco_msgs::Marker & marker_i = marker_msg_->markers.at(i);
186  marker_i.header.stamp = curr_stamp;
187  marker_i.id = markers_.at(i).id;
188  marker_i.confidence = 1.0;
189  }
190 
191  // if there is camera info let's do 3D stuff
192  if(useCamInfo_)
193  {
194  //get the current transform from the camera frame to output ref frame
195  tf::StampedTransform cameraToReference;
196  cameraToReference.setIdentity();
197 
198  if ( reference_frame_ != camera_frame_ )
199  {
200  getTransform(reference_frame_,
201  camera_frame_,
202  cameraToReference);
203  }
204 
205  //Now find the transform for each detected marker
206  for(size_t i=0; i<markers_.size(); ++i)
207  {
208  aruco_msgs::Marker & marker_i = marker_msg_->markers.at(i);
210  transform = static_cast<tf::Transform>(cameraToReference) * transform;
211  tf::poseTFToMsg(transform, marker_i.pose.pose);
212  marker_i.header.frame_id = reference_frame_;
213  }
214  }
215 
216  //publish marker array
217  if (marker_msg_->markers.size() > 0)
218  marker_pub_.publish(marker_msg_);
219  }
220 
221  if(publishMarkersList)
222  {
223  marker_list_msg_.data.resize(markers_.size());
224  for(size_t i=0; i<markers_.size(); ++i)
225  marker_list_msg_.data[i] = markers_[i].id;
226 
227  marker_list_pub_.publish(marker_list_msg_);
228  }
229 
230  // Draw detected markers on the image for visualization
231  for(size_t i=0; i<markers_.size(); ++i)
232  {
233  markers_[i].draw(inImage_,cv::Scalar(0,0,255),2);
234  }
235 
236  //draw a 3d cube in each marker if there is 3d info
237  if(camParam_.isValid() && marker_size_!=-1)
238  {
239  for(size_t i=0; i<markers_.size(); ++i)
240  aruco::CvDrawingUtils::draw3dAxis(inImage_, markers_[i], camParam_);
241  }
242 
243  // publish input image with markers drawn on it
244  if(publishImage)
245  {
246  //show input with augmented information
247  cv_bridge::CvImage out_msg;
248  out_msg.header.stamp = curr_stamp;
250  out_msg.image = inImage_;
251  image_pub_.publish(out_msg.toImageMsg());
252  }
253 
254  // publish image after internal image processing
255  if(publishDebug)
256  {
257  //show also the internal image resulting from the threshold operation
258  cv_bridge::CvImage debug_msg;
259  debug_msg.header.stamp = curr_stamp;
261  debug_msg.image = mDetector_.getThresholdedImage();
262  debug_pub_.publish(debug_msg.toImageMsg());
263  }
264 
265  }
266  catch (cv_bridge::Exception& e)
267  {
268  ROS_ERROR("cv_bridge exception: %s", e.what());
269  }
270  }
271 };
272 
273 
274 int main(int argc,char **argv)
275 {
276  ros::init(argc, argv, "aruco_marker_publisher");
277 
279 
280  ros::spin();
281 }
std_msgs::UInt32MultiArray marker_list_msg_
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)
image_transport::Publisher debug_pub_
image_transport::ImageTransport it_
void publish(const boost::shared_ptr< M > &message) const
aruco_msgs::MarkerArray::Ptr marker_msg_
int main(int argc, char **argv)
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()
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
tf::Transform arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis=true)
vector< aruco::Marker > markers_
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)
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
void image_callback(const sensor_msgs::ImageConstPtr &msg)
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)
static Time now()
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header header


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