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


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