simple_double.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  ********************************/
28 
37 #include <iostream>
38 #include <aruco/aruco.h>
39 #include <aruco/cvdrawingutils.h>
40 
41 #include <ros/ros.h>
43 #include <cv_bridge/cv_bridge.h>
47 #include <tf/transform_datatypes.h>
48 
49 #include <dynamic_reconfigure/server.h>
50 #include <aruco_ros/ArucoThresholdConfig.h>
51 
52 cv::Mat inImage;
57 std::vector<aruco::Marker> markers;
64 std::string child_name1;
65 std::string parent_name;
66 std::string child_name2;
67 
68 double marker_size;
71 
72 void image_callback(const sensor_msgs::ImageConstPtr& msg)
73 {
74  double ticksBefore = cv::getTickCount();
75  static tf::TransformBroadcaster br;
77  {
78  ros::Time curr_stamp = msg->header.stamp;
79  cv_bridge::CvImagePtr cv_ptr;
80  try
81  {
83  inImage = cv_ptr->image;
84 
86  {
87  ROS_WARN("normalizeImageIllumination is unimplemented!");
88 // cv::Mat inImageNorm;
89 // pal_vision_util::dctNormalization(inImage, inImageNorm, dctComponentsToRemove);
90 // inImage = inImageNorm;
91  }
92 
93  // detection results will go into "markers"
94  markers.clear();
95  // ok, let's detect
97  // for each marker, draw info and its boundaries in the image
98  for (unsigned int i = 0; i < markers.size(); ++i)
99  {
100  // only publishing the selected marker
101  if (markers[i].id == marker_id1)
102  {
104  br.sendTransform(tf::StampedTransform(transform, curr_stamp, parent_name, child_name1));
105  geometry_msgs::Pose poseMsg;
106  tf::poseTFToMsg(transform, poseMsg);
107  pose_pub1.publish(poseMsg);
108  }
109  else if (markers[i].id == marker_id2)
110  {
112  br.sendTransform(tf::StampedTransform(transform, curr_stamp, parent_name, child_name2));
113  geometry_msgs::Pose poseMsg;
114  tf::poseTFToMsg(transform, poseMsg);
115  pose_pub2.publish(poseMsg);
116  }
117 
118  // but drawing all the detected markers
119  markers[i].draw(inImage, cv::Scalar(0, 0, 255), 2);
120  }
121 
122  // paint a circle in the center of the image
123  cv::circle(inImage, cv::Point(inImage.cols / 2, inImage.rows / 2), 4, cv::Scalar(0, 255, 0), 1);
124 
125  if (markers.size() == 2)
126  {
127  float x[2], y[2], u[2], v[2];
128  for (unsigned int i = 0; i < 2; ++i)
129  {
131  "Marker(" << i << ") at camera coordinates = (" << markers[i].Tvec.at<float>(0,0) << ", " << markers[i].Tvec.at<float>(1,0) << ", " << markers[i].Tvec.at<float>(2,0));
132  // normalized coordinates of the marker
133  x[i] = markers[i].Tvec.at<float>(0, 0) / markers[i].Tvec.at<float>(2, 0);
134  y[i] = markers[i].Tvec.at<float>(1, 0) / markers[i].Tvec.at<float>(2, 0);
135  // undistorted pixel
136  u[i] = x[i] * camParam.CameraMatrix.at<float>(0, 0) + camParam.CameraMatrix.at<float>(0, 2);
137  v[i] = y[i] * camParam.CameraMatrix.at<float>(1, 1) + camParam.CameraMatrix.at<float>(1, 2);
138  }
139 
141  "Mid point between the two markers in the image = (" << (x[0]+x[1])/2 << ", " << (y[0]+y[1])/2 << ")");
142 
143 // // paint a circle in the mid point of the normalized coordinates of both markers
144 // cv::circle(inImage, cv::Point((u[0] + u[1]) / 2, (v[0] + v[1]) / 2), 3, cv::Scalar(0, 0, 255), cv::FILLED);
145 
146  // compute the midpoint in 3D:
147  float midPoint3D[3]; // 3D point
148  for (unsigned int i = 0; i < 3; ++i)
149  midPoint3D[i] = (markers[0].Tvec.at<float>(i, 0) + markers[1].Tvec.at<float>(i, 0)) / 2;
150  // now project the 3D mid point to normalized coordinates
151  float midPointNormalized[2];
152  midPointNormalized[0] = midPoint3D[0] / midPoint3D[2]; //x
153  midPointNormalized[1] = midPoint3D[1] / midPoint3D[2]; //y
154  u[0] = midPointNormalized[0] * camParam.CameraMatrix.at<float>(0, 0) + camParam.CameraMatrix.at<float>(0, 2);
155  v[0] = midPointNormalized[1] * camParam.CameraMatrix.at<float>(1, 1) + camParam.CameraMatrix.at<float>(1, 2);
156 
158  "3D Mid point between the two markers in undistorted pixel coordinates = (" << u[0] << ", " << v[0] << ")");
159 
160  // paint a circle in the mid point of the normalized coordinates of both markers
161  cv::circle(inImage, cv::Point(u[0], v[0]), 3, cv::Scalar(0, 0, 255), cv::FILLED);
162 
163  }
164 
165  // draw a 3D cube in each marker if there is 3D info
166  if (camParam.isValid() && marker_size != -1)
167  {
168  for (unsigned int i = 0; i < markers.size(); ++i)
169  {
171  }
172  }
173 
174  if (image_pub.getNumSubscribers() > 0)
175  {
176  // show input with augmented information
177  cv_bridge::CvImage out_msg;
178  out_msg.header.stamp = curr_stamp;
180  out_msg.image = inImage;
181  image_pub.publish(out_msg.toImageMsg());
182  }
183 
184  if (debug_pub.getNumSubscribers() > 0)
185  {
186  // show also the internal image resulting from the threshold operation
187  cv_bridge::CvImage debug_msg;
188  debug_msg.header.stamp = curr_stamp;
190  debug_msg.image = mDetector.getThresholdedImage();
191  debug_pub.publish(debug_msg.toImageMsg());
192  }
193 
194  ROS_DEBUG("runtime: %f ms", 1000 * (cv::getTickCount() - ticksBefore) / cv::getTickFrequency());
195  }
196  catch (cv_bridge::Exception& e)
197  {
198  ROS_ERROR("cv_bridge exception: %s", e.what());
199  return;
200  }
201  }
202 }
203 
204 // wait for one camerainfo, then shut down that subscriber
205 void cam_info_callback(const sensor_msgs::CameraInfo &msg)
206 {
208  cam_info_received = true;
210 }
211 
212 void reconf_callback(aruco_ros::ArucoThresholdConfig &config, std::uint32_t level)
213 {
214  mDetector.setDetectionMode(aruco::DetectionMode(config.detection_mode), config.min_image_size);
215  normalizeImageIllumination = config.normalizeImage;
216  dctComponentsToRemove = config.dctComponentsToRemove;
217 }
218 
219 int main(int argc, char **argv)
220 {
221  ros::init(argc, argv, "aruco_simple");
222  ros::NodeHandle nh("~");
224 
225  dynamic_reconfigure::Server<aruco_ros::ArucoThresholdConfig> server;
226  dynamic_reconfigure::Server<aruco_ros::ArucoThresholdConfig>::CallbackType f_;
227  f_ = boost::bind(&reconf_callback, _1, _2);
228  server.setCallback(f_);
229 
231 
232  nh.param<bool>("image_is_rectified", useRectifiedImages, true);
233  ROS_INFO_STREAM("Image is rectified: " << useRectifiedImages);
234 
235  image_transport::Subscriber image_sub = it.subscribe("/image", 1, &image_callback);
236  cam_info_sub = nh.subscribe("/camera_info", 1, &cam_info_callback);
237 
238  cam_info_received = false;
239  image_pub = it.advertise("result", 1);
240  debug_pub = it.advertise("debug", 1);
241  pose_pub1 = nh.advertise<geometry_msgs::Pose>("pose", 100);
242  pose_pub2 = nh.advertise<geometry_msgs::Pose>("pose2", 100);
243 
244  nh.param<double>("marker_size", marker_size, 0.05);
245  nh.param<int>("marker_id1", marker_id1, 582);
246  nh.param<int>("marker_id2", marker_id2, 26);
247  nh.param<bool>("normalizeImage", normalizeImageIllumination, true);
248  nh.param<int>("dct_components_to_remove", dctComponentsToRemove, 2);
249  if (dctComponentsToRemove == 0)
251  nh.param<std::string>("parent_name", parent_name, "");
252  nh.param<std::string>("child_name1", child_name1, "");
253  nh.param<std::string>("child_name2", child_name2, "");
254 
255  if (parent_name == "" || child_name1 == "" || child_name2 == "")
256  {
257  ROS_ERROR("parent_name and/or child_name was not set!");
258  return -1;
259  }
260 
261  ROS_INFO("ArUco node started with marker size of %f meters and marker ids to track: %d, %d", marker_size, marker_id1,
262  marker_id2);
263  ROS_INFO("ArUco node will publish pose to TF with (%s, %s) and (%s, %s) as (parent,child).", parent_name.c_str(),
264  child_name1.c_str(), parent_name.c_str(), child_name2.c_str());
265 
266  ros::spin();
267 }
cvdrawingutils.h
aruco_ros_utils.h
ros::Publisher
useRectifiedImages
bool useRectifiedImages
Definition: simple_double.cpp:54
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
image_encodings.h
aruco.h
image_transport::ImageTransport
reconf_callback
void reconf_callback(aruco_ros::ArucoThresholdConfig &config, std::uint32_t level)
Definition: simple_double.cpp:212
child_name2
std::string child_name2
Definition: simple_double.cpp:66
boost::shared_ptr
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
main
int main(int argc, char **argv)
Definition: simple_double.cpp:219
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
marker_id2
int marker_id2
Definition: simple_double.cpp:70
aruco::CameraParameters
ros.h
image_transport::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
camParam
aruco::CameraParameters camParam
Definition: simple_double.cpp:53
debug_pub
image_transport::Publisher debug_pub
Definition: simple_double.cpp:61
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()
aruco::CameraParameters::isValid
bool isValid() const
cv_bridge::Exception
sensor_msgs::image_encodings::RGB8
const std::string RGB8
marker_id1
int marker_id1
Definition: simple_double.cpp:69
tf::StampedTransform
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
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
inImage
cv::Mat inImage
Definition: simple_double.cpp:52
cam_info_received
bool cam_info_received
Definition: simple_double.cpp:59
aruco::CvDrawingUtils::draw3dCube
static void draw3dCube(cv::Mat &Image, Marker &m, const CameraParameters &CP, int lineSize=1, bool setYperpendicular=false)
aruco::CameraParameters::CameraMatrix
cv::Mat CameraMatrix
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())
child_name1
std::string child_name1
Definition: simple_double.cpp:64
tf::TransformBroadcaster
cam_info_sub
ros::Subscriber cam_info_sub
Definition: simple_double.cpp:58
image_pub
image_transport::Publisher image_pub
Definition: simple_double.cpp:60
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_WARN
#define ROS_WARN(...)
aruco_ros::arucoMarker2Tf
tf::Transform arucoMarker2Tf(const aruco::Marker &marker)
Definition: aruco_ros_utils.cpp:59
cam_info_callback
void cam_info_callback(const sensor_msgs::CameraInfo &msg)
Definition: simple_double.cpp:205
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())
pose_pub1
ros::Publisher pose_pub1
Definition: simple_double.cpp:62
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
tf::Transform
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
pose_pub2
ros::Publisher pose_pub2
Definition: simple_double.cpp:63
image_transport.h
dctComponentsToRemove
int dctComponentsToRemove
Definition: simple_double.cpp:55
mDetector
aruco::MarkerDetector mDetector
Definition: simple_double.cpp:56
transform_datatypes.h
ros::Time
cv_bridge::CvImage::encoding
std::string encoding
image_transport::Publisher
sensor_msgs::image_encodings::MONO8
const std::string MONO8
aruco::MarkerDetector
marker_size
double marker_size
Definition: simple_double.cpp:68
markers
std::vector< aruco::Marker > markers
Definition: simple_double.cpp:57
cv_bridge.h
ROS_ERROR
#define ROS_ERROR(...)
cv_bridge::CvImage
aruco::DetectionMode
DetectionMode
parent_name
std::string parent_name
Definition: simple_double.cpp:65
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
normalizeImageIllumination
bool normalizeImageIllumination
Definition: simple_double.cpp:54
ROS_INFO
#define ROS_INFO(...)
image_callback
void image_callback(const sensor_msgs::ImageConstPtr &msg)
Definition: simple_double.cpp:72
cv_bridge::CvImage::image
cv::Mat image
ros::NodeHandle
aruco::MarkerDetector::getThresholdedImage
cv::Mat getThresholdedImage(uint32_t idx=0)
ros::Subscriber


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