old/aruco_ros/src/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 <opencv2/core/core.hpp>
42 #include <ros/ros.h>
44 #include <cv_bridge/cv_bridge.h>
46 #include <aruco_ros/aruco_ros_utils.h>
48 #include <tf/transform_datatypes.h>
49 
50 #include <dynamic_reconfigure/server.h>
51 #include <aruco_ros/ArucoThresholdConfig.h>
52 
53 using namespace cv;
54 using namespace aruco;
55 
56 cv::Mat inImage;
61 vector<Marker> markers;
68 std::string child_name1;
69 std::string parent_name;
70 std::string child_name2;
71 
72 double marker_size;
75 
76 void image_callback(const sensor_msgs::ImageConstPtr& msg)
77 {
78  double ticksBefore = cv::getTickCount();
79  static tf::TransformBroadcaster br;
81  {
82  ros::Time curr_stamp(ros::Time::now());
83  cv_bridge::CvImagePtr cv_ptr;
84  try
85  {
87  inImage = cv_ptr->image;
88 
90  {
91  ROS_WARN("normalizeImageIllumination is unimplemented!");
92  //cv::Mat inImageNorm;
93  //pal_vision_util::dctNormalization(inImage, inImageNorm, dctComponentsToRemove);
94  //inImage = inImageNorm;
95  }
96 
97  //detection results will go into "markers"
98  markers.clear();
99  //Ok, let's detect
100  mDetector.detect(inImage, markers, camParam, marker_size);
101  //for each marker, draw info and its boundaries in the image
102  for(unsigned int i=0; i<markers.size(); ++i)
103  {
104  // only publishing the selected marker
105  if ( markers[i].id == marker_id1 )
106  {
108  br.sendTransform(tf::StampedTransform(transform, curr_stamp,
110  geometry_msgs::Pose poseMsg;
111  tf::poseTFToMsg(transform, poseMsg);
112  pose_pub1.publish(poseMsg);
113  }
114  else if ( markers[i].id == marker_id2 )
115  {
117  br.sendTransform(tf::StampedTransform(transform, curr_stamp,
119  geometry_msgs::Pose poseMsg;
120  tf::poseTFToMsg(transform, poseMsg);
121  pose_pub2.publish(poseMsg);
122  }
123 
124  // but drawing all the detected markers
125  markers[i].draw(inImage,Scalar(0,0,255),2);
126  }
127 
128  //paint a circle in the center of the image
129  cv::circle(inImage, cv::Point(inImage.cols/2, inImage.rows/2), 4, cv::Scalar(0,255,0), 1);
130 
131  if ( markers.size() == 2 )
132  {
133  float x[2], y[2], u[2], v[2];
134  for (unsigned int i = 0; i < 2; ++i)
135  {
136  ROS_DEBUG_STREAM("Marker(" << i << ") at camera coordinates = ("
137  << markers[i].Tvec.at<float>(0,0) << ", "
138  << markers[i].Tvec.at<float>(1,0) << ", "
139  << markers[i].Tvec.at<float>(2,0));
140  //normalized coordinates of the marker
141  x[i] = markers[i].Tvec.at<float>(0,0)/markers[i].Tvec.at<float>(2,0);
142  y[i] = markers[i].Tvec.at<float>(1,0)/markers[i].Tvec.at<float>(2,0);
143  //undistorted pixel
144  u[i] = x[i]*camParam.CameraMatrix.at<float>(0,0) +
145  camParam.CameraMatrix.at<float>(0,2);
146  v[i] = y[i]*camParam.CameraMatrix.at<float>(1,1) +
147  camParam.CameraMatrix.at<float>(1,2);
148  }
149 
150  ROS_DEBUG_STREAM("Mid point between the two markers in the image = ("
151  << (x[0]+x[1])/2 << ", " << (y[0]+y[1])/2 << ")");
152 
153  // //paint a circle in the mid point of the normalized coordinates of both markers
154  // cv::circle(inImage,
155  // cv::Point((u[0]+u[1])/2, (v[0]+v[1])/2),
156  // 3, cv::Scalar(0,0,255), CV_FILLED);
157 
158 
159  //compute the midpoint in 3D:
160  float midPoint3D[3]; //3D point
161  for (unsigned int i = 0; i < 3; ++i )
162  midPoint3D[i] = ( markers[0].Tvec.at<float>(i,0) +
163  markers[1].Tvec.at<float>(i,0) ) / 2;
164  //now project the 3D mid point to normalized coordinates
165  float midPointNormalized[2];
166  midPointNormalized[0] = midPoint3D[0]/midPoint3D[2]; //x
167  midPointNormalized[1] = midPoint3D[1]/midPoint3D[2]; //y
168  u[0] = midPointNormalized[0]*camParam.CameraMatrix.at<float>(0,0) +
169  camParam.CameraMatrix.at<float>(0,2);
170  v[0] = midPointNormalized[1]*camParam.CameraMatrix.at<float>(1,1) +
171  camParam.CameraMatrix.at<float>(1,2);
172 
173  ROS_DEBUG_STREAM("3D Mid point between the two markers in undistorted pixel coordinates = ("
174  << u[0] << ", " << v[0] << ")");
175 
176  //paint a circle in the mid point of the normalized coordinates of both markers
177  cv::circle(inImage,
178  cv::Point(u[0], v[0]),
179  3, cv::Scalar(0,0,255), CV_FILLED);
180 
181  }
182 
183  //draw a 3d cube in each marker if there is 3d info
184  if(camParam.isValid() && marker_size!=-1)
185  {
186  for(unsigned int i=0; i<markers.size(); ++i)
187  {
188  CvDrawingUtils::draw3dCube(inImage, markers[i], camParam);
189  }
190  }
191 
192  if(image_pub.getNumSubscribers() > 0)
193  {
194  //show input with augmented information
195  cv_bridge::CvImage out_msg;
196  out_msg.header.stamp = curr_stamp;
198  out_msg.image = inImage;
199  image_pub.publish(out_msg.toImageMsg());
200  }
201 
202  if(debug_pub.getNumSubscribers() > 0)
203  {
204  //show also the internal image resulting from the threshold operation
205  cv_bridge::CvImage debug_msg;
206  debug_msg.header.stamp = curr_stamp;
208  debug_msg.image = mDetector.getThresholdedImage();
209  debug_pub.publish(debug_msg.toImageMsg());
210  }
211 
212  ROS_DEBUG("runtime: %f ms",
213  1000*(cv::getTickCount() - ticksBefore)/cv::getTickFrequency());
214  }
215  catch (cv_bridge::Exception& e)
216  {
217  ROS_ERROR("cv_bridge exception: %s", e.what());
218  return;
219  }
220  }
221 }
222 
223 // wait for one camerainfo, then shut down that subscriber
224 void cam_info_callback(const sensor_msgs::CameraInfo &msg)
225 {
227  cam_info_received = true;
228  cam_info_sub.shutdown();
229 }
230 
231 void reconf_callback(aruco_ros::ArucoThresholdConfig &config, uint32_t level)
232 {
233  mDetector.setThresholdParams(config.param1,config.param2);
234  normalizeImageIllumination = config.normalizeImage;
235  dctComponentsToRemove = config.dctComponentsToRemove;
236 }
237 
238 int main(int argc,char **argv)
239 {
240  ros::init(argc, argv, "aruco_simple");
241  ros::NodeHandle nh("~");
243 
244  dynamic_reconfigure::Server<aruco_ros::ArucoThresholdConfig> server;
245  dynamic_reconfigure::Server<aruco_ros::ArucoThresholdConfig>::CallbackType f_;
246  f_ = boost::bind(&reconf_callback, _1, _2);
247  server.setCallback(f_);
248 
250 
251  nh.param<bool>("image_is_rectified", useRectifiedImages, true);
252  ROS_INFO_STREAM("Image is rectified: " << useRectifiedImages);
253 
254  image_transport::Subscriber image_sub = it.subscribe("/image", 1, &image_callback);
255  cam_info_sub = nh.subscribe("/camera_info", 1, &cam_info_callback);
256 
257  cam_info_received = false;
258  image_pub = it.advertise("result", 1);
259  debug_pub = it.advertise("debug", 1);
260  pose_pub1 = nh.advertise<geometry_msgs::Pose>("pose", 100);
261  pose_pub2 = nh.advertise<geometry_msgs::Pose>("pose2", 100);
262 
263  nh.param<double>("marker_size", marker_size, 0.05);
264  nh.param<int>("marker_id1", marker_id1, 582);
265  nh.param<int>("marker_id2", marker_id2, 26);
266  nh.param<bool>("normalizeImage", normalizeImageIllumination, true);
267  nh.param<int>("dct_components_to_remove", dctComponentsToRemove, 2);
268  if(dctComponentsToRemove == 0)
269  normalizeImageIllumination = false;
270  nh.param<std::string>("parent_name", parent_name, "");
271  nh.param<std::string>("child_name1", child_name1, "");
272  nh.param<std::string>("child_name2", child_name2, "");
273 
274  if(parent_name == "" || child_name1 == "" || child_name2 == "")
275  {
276  ROS_ERROR("parent_name and/or child_name was not set!");
277  return -1;
278  }
279 
280  ROS_INFO("Aruco node started with marker size of %f meters and marker ids to track: %d, %d",
281  marker_size, marker_id1, marker_id2);
282  ROS_INFO("Aruco node will publish pose to TF with (%s, %s) and (%s, %s) as (parent,child).",
283  parent_name.c_str(), child_name1.c_str(), parent_name.c_str(), child_name2.c_str());
284 
285  ros::spin();
286 }
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 setThresholdParams(double param1, double param2)
aruco::CameraParameters camParam
ros::Publisher pose_pub1
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 reconf_callback(aruco_ros::ArucoThresholdConfig &config, uint32_t level)
ros::Subscriber cam_info_sub
MarkerDetector mDetector
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)
std::string child_name1
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string child_name2
#define ROS_WARN(...)
ros::Publisher pose_pub2
uint32_t getNumSubscribers() const
ROSCPP_DECL void spin(Spinner &spinner)
pcl::PointCloud< myPointXYZRID > transform(pcl::PointCloud< myPointXYZRID > pc, float x, float y, float z, float rot_x, float rot_y, float rot_z)
image_transport::Publisher debug_pub
tf::Transform arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis=true)
void publish(const sensor_msgs::Image &message) const
void cam_info_callback(const sensor_msgs::CameraInfo &msg)
#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)
TFSIMD_FORCE_INLINE const tfScalar & x() 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 ...
#define ROS_DEBUG_STREAM(args)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
#define ROS_INFO_STREAM(args)
int main(int argc, char **argv)
config
static Time now()
vector< Marker > markers
std::string parent_name
void image_callback(const sensor_msgs::ImageConstPtr &msg)
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header header
bool normalizeImageIllumination
#define ROS_DEBUG(...)


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