13 #include "apriltag_pose.h" 14 #include "common/homography.h" 17 #define FORMAT_VALUE std::fixed << std::right << std::setprecision(3) << std::setw(6) 24 for(
int r=0;
r<9; ++
r){ tf.
rotation[
r] =
static_cast<float>(R[
r]); }
65 std::stringstream ss; ss <<
"R:";
76 tf = tag36h11_create();
77 td = apriltag_detector_create();
78 apriltag_detector_add_family(
td,
tf);
80 td->quad_decimate = 1.0;
86 info.tagsize = tagsize;
91 apriltag_detector_destroy(
td);
96 std::shared_ptr<zarray_t>
det;
97 std::vector<std::shared_ptr<apriltag_pose_t>>
pose_raw;
101 apriltag_detection_t*
get(
int t)
const { apriltag_detection_t* ptr; zarray_get(det.get(),
t, &ptr);
return ptr; }
103 int size()
const {
return pose_in_camera.size(); }
112 tags.
det = std::shared_ptr<zarray_t>(apriltag_detector_detect(
td, &
img), apriltag_detections_destroy);
117 for(
int t=0, num_of_tags=(
int)tags.
size();
t<num_of_tags; ++
t)
123 estimate_pose_for_tag_homography(&info_, tags.
pose_raw[
t].get());
124 for(
auto c : {1,2,4,5,7,8}){ tags.
pose_raw[
t]->R->data[
c] *= -1; }
134 apriltag_family_t *
tf;
135 apriltag_detector_t *
td;
136 apriltag_detection_info_t
info;
142 for(
int t=0, num_of_tags=tags.
size();
t<num_of_tags; ++
t){
145 tags.
pose_in_world[
t] = tf_world_to_body * tf_body_to_fisheye * tf_fisheye_to_tag;
152 double corr_arr[4][4];
153 for(
int c=0;
c<4; ++
c){
156 corr_arr[
c][0] = (
c==0 ||
c==3) ? -1 : 1;
157 corr_arr[
c][1] = (
c==0 ||
c==1) ? -1 : 1;
158 corr_arr[
c][2] = src.p[
c][0];
159 corr_arr[
c][3] = src.p[
c][1];
161 if(src.H ==
nullptr) { src.H = matd_create(3, 3); }
166 float fpt[3], fpx[2] = { (float)px[0], (
float)px[1] };
173 int main(
int argc,
char * argv[])
try 190 const int fisheye_sensor_idx = 1;
191 auto pipe_profile = pipe.
start(cfg);
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;
198 apriltag_manager tag_manager(fisheye_intrinsics, body_fisheye_extr, tag_size_m);
205 auto fisheye_frame =
frames.get_fisheye_frame(fisheye_sensor_idx);
207 auto camera_pose =
frames.get_pose_frame().get_pose_data();
211 fisheye_frame.keep();
216 if(
tags.pose_in_camera.size() == 0) {
217 std::cout <<
"frame " << fn <<
"|no Apriltag detections" << std::endl;
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) <<
"|";
222 std::cout << std::setw(ss.str().size()) <<
" " <<
"world " <<
236 catch (
const std::exception& e)
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],
261 double epsilon = 1e-10;
267 int max_val_idx = -1;
276 if (max_val < epsilon) {
277 fprintf(stderr,
"WRN: Matrix is singular.\n");
281 if (max_val_idx !=
col) {
282 for (
int i =
col;
i < 9;
i++) {
284 A[
col*9 +
i] = A[max_val_idx*9 +
i];
285 A[max_val_idx*9 +
i] =
tmp;
290 for (
int i =
col + 1;
i < 8;
i++) {
293 for (
int j =
col + 1;
j < 9;
j++) {
294 A[
i*9 +
j] -= f*A[
col*9 +
j];
302 for (
int i =
col + 1;
i < 8;
i++) {
303 sum += A[
col*9 +
i]*A[
i*9 + 8];
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)
unsigned int tracker_confidence
static void apriltag_pose_destroy(apriltag_pose_t *p)
apriltag_detection_info_t info
apriltag_array_t detect(unsigned char *gray, const rs2_pose *camera_pose) const
const void * get_data() const
GLsizei const GLchar *const * string
::realsense_legacy_msgs::pose_< std::allocator< void > > pose
GLboolean GLboolean GLboolean GLboolean a
Quaternion used to represent rotation.
const std::string & get_failed_args() const
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)
std::shared_ptr< zarray_t > det
int main(int argc, char *argv[])
void homography_compute2(const double c[4][4], matd_t *H)
stream_profile get_stream(rs2_stream stream_type, int stream_index=-1) const
transformation tf_body_to_fisheye
apriltag_manager(const rs2_intrinsics &_intr, const rs2_extrinsics _extr_b2f, double tagsize)
rs2_extrinsics transformation
static std::string print(const transformation &tf)
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...
apriltag_detection_t * get(int t) const
static void undistort(apriltag_detection_t &src, const rs2_intrinsics &intr)
3D vector in Euclidean coordinate space
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])
void enable_device_from_file(const std::string &file_name, bool repeat_playback=true)
std::vector< transformation > pose_in_camera
std::vector< transformation > pose_in_world
const std::string & get_failed_function() const