rs-pose-apriltag.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2019 Intel Corporation. All Rights Reserved.
3 #include <librealsense2/rs.hpp>
4 #include <librealsense2/rsutil.h>
5 #include <iostream>
6 #include <iomanip>
7 #include <sstream>
8 #include <chrono>
9 #include <future>
10 #include <math.h>
11 
12 #include "apriltag.h"
13 #include "apriltag_pose.h"
14 #include "common/homography.h"
15 #include "tag36h11.h"
16 
17 #define FORMAT_VALUE std::fixed << std::right << std::setprecision(3) << std::setw(6)
18 
19 void homography_compute2(const double c[4][4], matd_t* H);
20 
22 static transformation to_transform(const double R[9], const double t[3]) {
23  transformation tf;
24  for(int r=0; r<9; ++r){ tf.rotation[r] = static_cast<float>(R[r]); }
25  for(int i=0; i<3; ++i){ tf.translation[i] = static_cast<float>(t[i]); }
26  return tf;
27 }
28 
30  transformation tf;
31  tf.rotation[0] = q.w * q.w + q.x * q.x - q.y * q.y - q.z * q.z;
32  tf.rotation[1] = 2 * (q.x * q.y - q.w * q.z);
33  tf.rotation[2] = 2 * (q.x * q.z + q.w * q.y);
34  tf.rotation[3] = 2 * (q.x * q.y + q.w * q.z);
35  tf.rotation[4] = q.w * q.w - q.x * q.x + q.y * q.y - q.z * q.z;
36  tf.rotation[5] = 2 * (q.y * q.z - q.w * q.x);
37  tf.rotation[6] = 2 * (q.x * q.z - q.w * q.y);
38  tf.rotation[7] = 2 * (q.y * q.z + q.w * q.x);
39  tf.rotation[8] = q.w * q.w - q.x * q.x - q.y * q.y + q.z * q.z;
40  tf.translation[0] = t.x;
41  tf.translation[1] = t.y;
42  tf.translation[2] = t.z;
43  return tf;
44 }
45 
47  transformation tf;
48  tf.rotation[0] = a.rotation[0] * b.rotation[0] + a.rotation[1] * b.rotation[3] + a.rotation[2] * b.rotation[6];
49  tf.rotation[1] = a.rotation[0] * b.rotation[1] + a.rotation[1] * b.rotation[4] + a.rotation[2] * b.rotation[7];
50  tf.rotation[2] = a.rotation[0] * b.rotation[2] + a.rotation[1] * b.rotation[5] + a.rotation[2] * b.rotation[8];
51  tf.rotation[3] = a.rotation[3] * b.rotation[0] + a.rotation[4] * b.rotation[3] + a.rotation[5] * b.rotation[6];
52  tf.rotation[4] = a.rotation[3] * b.rotation[1] + a.rotation[4] * b.rotation[4] + a.rotation[5] * b.rotation[7];
53  tf.rotation[5] = a.rotation[3] * b.rotation[2] + a.rotation[4] * b.rotation[5] + a.rotation[5] * b.rotation[8];
54  tf.rotation[6] = a.rotation[6] * b.rotation[0] + a.rotation[7] * b.rotation[3] + a.rotation[8] * b.rotation[6];
55  tf.rotation[7] = a.rotation[6] * b.rotation[1] + a.rotation[7] * b.rotation[4] + a.rotation[8] * b.rotation[7];
56  tf.rotation[8] = a.rotation[6] * b.rotation[2] + a.rotation[7] * b.rotation[5] + a.rotation[8] * b.rotation[8];
57 
58  tf.translation[0] = a.rotation[0] * b.translation[0] + a.rotation[1] * b.translation[1] + a.rotation[2] * b.translation[2] + a.translation[0];
59  tf.translation[1] = a.rotation[3] * b.translation[0] + a.rotation[4] * b.translation[1] + a.rotation[5] * b.translation[2] + a.translation[1];
60  tf.translation[2] = a.rotation[6] * b.translation[0] + a.rotation[7] * b.translation[1] + a.rotation[8] * b.translation[2] + a.translation[2];
61  return tf;
62 }
63 
64 static std::string print(const transformation& tf) {
65  std::stringstream ss; ss << "R:";
66  for(const auto& r : tf.rotation){ ss << FORMAT_VALUE << r << ","; }
67  ss << "|t:";
68  for(const auto& t : tf.translation){ ss << FORMAT_VALUE << t << ","; }
69  return ss.str();
70 }
71 
73 public:
74  apriltag_manager(const rs2_intrinsics& _intr, const rs2_extrinsics _extr_b2f, double tagsize)
75  : intr(_intr), tf_body_to_fisheye(_extr_b2f) {
76  tf = tag36h11_create();
77  td = apriltag_detector_create();
78  apriltag_detector_add_family(td, tf);
79 
80  td->quad_decimate = 1.0;
81  td->quad_sigma = 0.0;
82  td->nthreads = 1;
83  td->debug = 0;
84  td->refine_edges = 1;
85 
86  info.tagsize = tagsize;
87  info.fx = info.fy = 1; //undistorted image with focal length = 1
88  info.cx = info.cy = 0; //undistorted image with principal point at (0,0)
89  }
91  apriltag_detector_destroy(td);
92  tag36h11_destroy(tf);
93  }
94 
96  std::shared_ptr<zarray_t> det;
97  std::vector<std::shared_ptr<apriltag_pose_t>> pose_raw; //tag pose from library
98  std::vector<transformation> pose_in_camera; //tag pose in camera coordinate
99  std::vector<transformation> pose_in_world; //tag pose in world coordinate
100 
101  apriltag_detection_t* get(int t) const { apriltag_detection_t* ptr; zarray_get(det.get(), t, &ptr); return ptr; }
102  int get_id(int t) const { return get(t)->id; }
103  int size() const { return pose_in_camera.size(); }
104  };
105 
106  static void apriltag_pose_destroy(apriltag_pose_t* p){ matd_destroy(p->R); matd_destroy(p->t); delete p;}
107 
108  apriltag_array_t detect(unsigned char* gray, const rs2_pose* camera_pose) const {
109  image_u8_t img{ intr.width, intr.height, intr.width, gray};
110 
112  tags.det = std::shared_ptr<zarray_t>(apriltag_detector_detect(td, &img), apriltag_detections_destroy);
113  tags.pose_in_camera.resize(zarray_size(tags.det.get()));
114  tags.pose_raw.resize(tags.size());
115 
116  auto info_ = info;
117  for(int t=0, num_of_tags=(int)tags.size(); t<num_of_tags; ++t)
118  {
119  tags.pose_raw[t] = std::shared_ptr<apriltag_pose_t>(new apriltag_pose_t(), apriltag_pose_destroy);
120 
121  undistort(*(info_.det = tags.get(t)), intr); //recompute tag corners on an undistorted image focal length = 1
122  //estimate_tag_pose(&info_, tags.pose_raw[t].get()); //(alternative) estimate tag pose in camera coordinate
123  estimate_pose_for_tag_homography(&info_, tags.pose_raw[t].get()); //estimate tag pose in camera coordinate
124  for(auto c : {1,2,4,5,7,8}){ tags.pose_raw[t]->R->data[c] *= -1; }
125 
126  tags.pose_in_camera[t] = to_transform(tags.pose_raw[t]->R->data, tags.pose_raw[t]->t->data);
127  }
128 
129  if(camera_pose){ compute_tag_pose_in_world(tags, *camera_pose); }
130  return tags;
131  }
132 
133 protected:
134  apriltag_family_t *tf;
135  apriltag_detector_t *td;
136  apriltag_detection_info_t info;
139 
140  void compute_tag_pose_in_world(apriltag_array_t& tags, const rs2_pose& camera_world_pose) const {
141  tags.pose_in_world.resize(tags.size());
142  for(int t=0, num_of_tags=tags.size(); t<num_of_tags; ++t){
143  auto tf_fisheye_to_tag = tags.pose_in_camera[t];
144  auto tf_world_to_body = to_transform(camera_world_pose.rotation, camera_world_pose.translation);
145  tags.pose_in_world[t] = tf_world_to_body * tf_body_to_fisheye * tf_fisheye_to_tag;
146  }
147  }
148 
149  static void undistort(apriltag_detection_t& src, const rs2_intrinsics& intr) {
150  deproject(src.c, intr, src.c);
151 
152  double corr_arr[4][4];
153  for(int c=0; c<4; ++c){
154  deproject(src.p[c], intr, src.p[c]);
155 
156  corr_arr[c][0] = (c==0 || c==3) ? -1 : 1; // tag corners in an ideal image
157  corr_arr[c][1] = (c==0 || c==1) ? -1 : 1; // tag corners in an ideal image
158  corr_arr[c][2] = src.p[c][0]; // tag corners in undistorted image focal length = 1
159  corr_arr[c][3] = src.p[c][1]; // tag corners in undistorted image focal length = 1
160  }
161  if(src.H == nullptr) { src.H = matd_create(3, 3); }
162  homography_compute2(corr_arr, src.H);
163  }
164 
165  static void deproject(double pt[2], const rs2_intrinsics& intr, const double px[2]) {
166  float fpt[3], fpx[2] = { (float)px[0], (float)px[1] };
167  rs2_deproject_pixel_to_point(fpt, &intr, fpx, 1.0f);
168  pt[0] = fpt[0];
169  pt[1] = fpt[1];
170  }
171 };
172 
173 int main(int argc, char * argv[]) try
174 {
175  // Declare RealSense pipeline, encapsulating the actual device and sensors
177  // Create a configuration for configuring the pipeline with a non default profile
179  // Add pose stream
181  // Enable both image streams
182  // Note: It is not currently possible to enable only one
185 
186  // replay
187  if(argc > 1){ cfg.enable_device_from_file(argv[1]); }
188 
189  // Start pipe and get camera calibrations
190  const int fisheye_sensor_idx = 1; //for the left fisheye lens of T265
191  auto pipe_profile = pipe.start(cfg);
192  auto fisheye_stream = pipe_profile.get_stream(RS2_STREAM_FISHEYE, fisheye_sensor_idx);
193  auto fisheye_intrinsics = fisheye_stream.as<rs2::video_stream_profile>().get_intrinsics();
194  auto body_fisheye_extr = fisheye_stream.get_extrinsics_to(pipe_profile.get_stream(RS2_STREAM_POSE));
195  const double tag_size_m = 0.144; // The expected size of the tag in meters. This is required to get the relative pose
196 
197  // Create an Apriltag detection manager
198  apriltag_manager tag_manager(fisheye_intrinsics, body_fisheye_extr, tag_size_m);
199 
200  // Main loop
201  while (true)
202  {
203  // Wait for the next set of frames from the camera
204  auto frames = pipe.wait_for_frames();
205  auto fisheye_frame = frames.get_fisheye_frame(fisheye_sensor_idx);
206  auto frame_number = fisheye_frame.get_frame_number();
207  auto camera_pose = frames.get_pose_frame().get_pose_data();
208 
209  if(frame_number % 6 == 0)
210  {
211  fisheye_frame.keep();
212 
213  std::async(std::launch::async, std::bind([&tag_manager](rs2::frame img, int fn, rs2_pose pose){
214  auto tags = tag_manager.detect((unsigned char*)img.get_data(), &pose);
215 
216  if(tags.pose_in_camera.size() == 0) {
217  std::cout << "frame " << fn << "|no Apriltag detections" << std::endl;
218  }
219  for(int t=0; t<tags.pose_in_camera.size(); ++t){
220  std::stringstream ss; ss << "frame " << fn << "|tag id: " << tags.get_id(t) << "|";
221  std::cout << ss.str() << "camera " << print(tags.pose_in_camera[t]) << std::endl;
222  std::cout << std::setw(ss.str().size()) << " " << "world " <<
223  (pose.tracker_confidence == 3 ? print(tags.pose_in_world[t]) : " NA ") << std::endl << std::endl;
224  }
225  }, fisheye_frame, frame_number, camera_pose));
226  }
227  }
228 
229  return EXIT_SUCCESS;
230 }
231 catch (const rs2::error & e)
232 {
233  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
234  return EXIT_FAILURE;
235 }
236 catch (const std::exception& e)
237 {
238  std::cerr << e.what() << std::endl;
239  return EXIT_FAILURE;
240 }
241 
242 //
243 // Re-compute homography between ideal standard tag image and undistorted tag corners for estimage_tag_pose().
244 //
245 // @param[in] c is 4 pairs of tag corners on ideal image and undistorted input image.
246 // @param[out] H is the output homography between ideal and undistorted input image.
247 // @see static void apriltag_manager::undistort(...)
248 //
249 void homography_compute2(const double c[4][4], matd_t* H) {
250  double A[] = {
251  c[0][0], c[0][1], 1, 0, 0, 0, -c[0][0]*c[0][2], -c[0][1]*c[0][2], c[0][2],
252  0, 0, 0, c[0][0], c[0][1], 1, -c[0][0]*c[0][3], -c[0][1]*c[0][3], c[0][3],
253  c[1][0], c[1][1], 1, 0, 0, 0, -c[1][0]*c[1][2], -c[1][1]*c[1][2], c[1][2],
254  0, 0, 0, c[1][0], c[1][1], 1, -c[1][0]*c[1][3], -c[1][1]*c[1][3], c[1][3],
255  c[2][0], c[2][1], 1, 0, 0, 0, -c[2][0]*c[2][2], -c[2][1]*c[2][2], c[2][2],
256  0, 0, 0, c[2][0], c[2][1], 1, -c[2][0]*c[2][3], -c[2][1]*c[2][3], c[2][3],
257  c[3][0], c[3][1], 1, 0, 0, 0, -c[3][0]*c[3][2], -c[3][1]*c[3][2], c[3][2],
258  0, 0, 0, c[3][0], c[3][1], 1, -c[3][0]*c[3][3], -c[3][1]*c[3][3], c[3][3],
259  };
260 
261  double epsilon = 1e-10;
262 
263  // Eliminate.
264  for (int col = 0; col < 8; col++) {
265  // Find best row to swap with.
266  double max_val = 0;
267  int max_val_idx = -1;
268  for (int row = col; row < 8; row++) {
269  double val = fabs(A[row*9 + col]);
270  if (val > max_val) {
271  max_val = val;
272  max_val_idx = row;
273  }
274  }
275 
276  if (max_val < epsilon) {
277  fprintf(stderr, "WRN: Matrix is singular.\n");
278  }
279 
280  // Swap to get best row.
281  if (max_val_idx != col) {
282  for (int i = col; i < 9; i++) {
283  double tmp = A[col*9 + i];
284  A[col*9 + i] = A[max_val_idx*9 + i];
285  A[max_val_idx*9 + i] = tmp;
286  }
287  }
288 
289  // Do eliminate.
290  for (int i = col + 1; i < 8; i++) {
291  double f = A[i*9 + col]/A[col*9 + col];
292  A[i*9 + col] = 0;
293  for (int j = col + 1; j < 9; j++) {
294  A[i*9 + j] -= f*A[col*9 + j];
295  }
296  }
297  }
298 
299  // Back solve.
300  for (int col = 7; col >=0; col--) {
301  double sum = 0;
302  for (int i = col + 1; i < 8; i++) {
303  sum += A[col*9 + i]*A[i*9 + 8];
304  }
305  A[col*9 + 8] = (A[col*9 + 8] - sum)/A[col*9 + col];
306  }
307  H->data[0] = A[8];
308  H->data[1] = A[17];
309  H->data[2] = A[26];
310  H->data[3] = A[35];
311  H->data[4] = A[44];
312  H->data[5] = A[53];
313  H->data[6] = A[62];
314  H->data[7] = A[71];
315  H->data[8] = 1;
316 }
std::vector< std::shared_ptr< apriltag_pose_t > > pose_raw
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
GLboolean GLboolean GLboolean b
GLenum GLenum GLsizei void * row
static transformation operator*(const transformation &a, const transformation &b)
float z
Definition: rs_types.h:131
unsigned int tracker_confidence
Definition: rs_types.h:148
#define FORMAT_VALUE
static void apriltag_pose_destroy(apriltag_pose_t *p)
GLfloat GLfloat p
Definition: glext.h:12687
float translation[3]
Definition: rs_sensor.h:99
rs2_intrinsics intr
apriltag_detection_info_t info
rs2_vector translation
Definition: rs_types.h:142
apriltag_array_t detect(unsigned char *gray, const rs2_pose *camera_pose) const
const void * get_data() const
Definition: rs_frame.hpp:545
GLsizei const GLchar *const * string
GLenum src
Definition: glext.h:1751
e
Definition: rmse.py:177
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
Definition: pose.h:88
float rotation[9]
Definition: rs_sensor.h:98
GLdouble t
GLboolean GLboolean GLboolean GLboolean a
GLuint GLfloat * val
const int H
Quaternion used to represent rotation.
Definition: rs_types.h:135
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
float y
Definition: rs_types.h:131
GLdouble f
void compute_tag_pose_in_world(apriltag_array_t &tags, const rs2_pose &camera_world_pose) const
static void rs2_deproject_pixel_to_point(float point[3], const struct rs2_intrinsics *intrin, const float pixel[2], float depth)
Definition: rsutil.h:83
std::shared_ptr< zarray_t > det
std::ostream & cout()
const GLubyte * c
Definition: glext.h:12690
GLdouble GLdouble r
int main(int argc, char *argv[])
void homography_compute2(const double c[4][4], matd_t *H)
apriltag_family_t * tf
rs2_quaternion rotation
Definition: rs_types.h:145
stream_profile get_stream(rs2_stream stream_type, int stream_index=-1) const
Definition: rs_pipeline.hpp:60
transformation tf_body_to_fisheye
GLint j
apriltag_manager(const rs2_intrinsics &_intr, const rs2_extrinsics _extr_b2f, double tagsize)
rs2_extrinsics transformation
static std::string print(const transformation &tf)
GLint void * img
string gray
Definition: log.py:29
float x
Definition: rs_types.h:131
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
Definition: rs_sensor.h:96
apriltag_detection_t * get(int t) const
static void undistort(apriltag_detection_t &src, const rs2_intrinsics &intr)
3D vector in Euclidean coordinate space
Definition: rs_types.h:129
GLdouble GLdouble GLdouble q
static transformation to_transform(const double R[9], const double t[3])
static void deproject(double pt[2], const rs2_intrinsics &intr, const double px[2])
Video stream intrinsics.
Definition: rs_types.h:58
std::ostream & cerr()
void enable_device_from_file(const std::string &file_name, bool repeat_playback=true)
int i
pipeline_profile start()
apriltag_detector_t * td
std::vector< transformation > pose_in_camera
std::vector< transformation > pose_in_world
const std::string & get_failed_function() const
Definition: rs_types.hpp:112


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:40