aruco_ros_utils.cpp
Go to the documentation of this file.
2 #include <ros/console.h>
3 #include <ros/assert.h>
4 #include <iostream>
6 
7 aruco::CameraParameters aruco_ros::rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo& cam_info,
8  bool useRectifiedParameters)
9 {
10  cv::Mat cameraMatrix(3, 3, CV_64FC1);
11  cv::Mat distorsionCoeff(4, 1, CV_64FC1);
12  cv::Size size(cam_info.height, cam_info.width);
13 
14  if ( useRectifiedParameters )
15  {
16  cameraMatrix.setTo(0);
17  cameraMatrix.at<double>(0,0) = cam_info.P[0]; cameraMatrix.at<double>(0,1) = cam_info.P[1]; cameraMatrix.at<double>(0,2) = cam_info.P[2];
18  cameraMatrix.at<double>(1,0) = cam_info.P[4]; cameraMatrix.at<double>(1,1) = cam_info.P[5]; cameraMatrix.at<double>(1,2) = cam_info.P[6];
19  cameraMatrix.at<double>(2,0) = cam_info.P[8]; cameraMatrix.at<double>(2,1) = cam_info.P[9]; cameraMatrix.at<double>(2,2) = cam_info.P[10];
20 
21  for(int i=0; i<4; ++i)
22  distorsionCoeff.at<double>(i, 0) = 0;
23  }
24  else
25  {
26  for(int i=0; i<9; ++i)
27  cameraMatrix.at<double>(i%3, i-(i%3)*3) = cam_info.K[i];
28 
29  if(cam_info.D.size() == 4)
30  {
31  for(int i=0; i<4; ++i)
32  distorsionCoeff.at<double>(i, 0) = cam_info.D[i];
33  }
34  else
35  {
36  ROS_WARN("length of camera_info D vector is not 4, assuming zero distortion...");
37  for(int i=0; i<4; ++i)
38  distorsionCoeff.at<double>(i, 0) = 0;
39  }
40  }
41 
42  return aruco::CameraParameters(cameraMatrix, distorsionCoeff, size);
43 }
44 
45 tf::Transform aruco_ros::arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis)
46 {
47  cv::Mat rot(3, 3, CV_64FC1);
48  cv::Mat Rvec64;
49  marker.Rvec.convertTo(Rvec64, CV_64FC1);
50  cv::Rodrigues(Rvec64, rot);
51  cv::Mat tran64;
52  marker.Tvec.convertTo(tran64, CV_64FC1);
53 
54  // Rotate axis direction as to fit ROS (?)
55  if (rotate_marker_axis)
56  {
57  cv::Mat rotate_to_ros(3, 3, CV_64FC1);
58  // -1 0 0
59  // 0 0 1
60  // 0 1 0
61  rotate_to_ros.at<double>(0,0) = -1.0;
62  rotate_to_ros.at<double>(0,1) = 0.0;
63  rotate_to_ros.at<double>(0,2) = 0.0;
64  rotate_to_ros.at<double>(1,0) = 0.0;
65  rotate_to_ros.at<double>(1,1) = 0.0;
66  rotate_to_ros.at<double>(1,2) = 1.0;
67  rotate_to_ros.at<double>(2,0) = 0.0;
68  rotate_to_ros.at<double>(2,1) = 1.0;
69  rotate_to_ros.at<double>(2,2) = 0.0;
70  rot = rot*rotate_to_ros.t();
71  }
72  tf::Matrix3x3 tf_rot(rot.at<double>(0,0), rot.at<double>(0,1), rot.at<double>(0,2),
73  rot.at<double>(1,0), rot.at<double>(1,1), rot.at<double>(1,2),
74  rot.at<double>(2,0), rot.at<double>(2,1), rot.at<double>(2,2));
75 
76  tf::Vector3 tf_orig(tran64.at<double>(0,0), tran64.at<double>(1,0), tran64.at<double>(2,0));
77 
78 
79  return tf::Transform(tf_rot, tf_orig);
80 }
#define ROS_WARN(...)
tf::Transform arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis=true)
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...


aruco_ros
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Wed Sep 2 2020 04:02:14