geolib2
msg_conversions.cpp
Go to the documentation of this file.
2 
3 namespace geo {
4 
5 void convert(const geo::Mesh& m, shape_msgs::Mesh& msg) {
6  const std::vector<Vector3>& points = m.getPoints();
7  const std::vector<TriangleI>& triangles = m.getTriangleIs();
8 
9  for (std::vector<Vector3>::const_iterator it = points.begin(); it != points.end(); ++it)
10  {
11  geometry_msgs::Point point;
12  convert(*it, point);
13  msg.vertices.push_back(point);
14  }
15 
16  for (std::vector<TriangleI>::const_iterator it = triangles.begin(); it != triangles.end(); ++it)
17  {
18  shape_msgs::MeshTriangle meshtriangle;
19  convert(*it, meshtriangle);
20  msg.triangles.push_back(meshtriangle);
21  }
22 }
23 
24 void convert(const geo::DepthCamera& cam_model, sensor_msgs::CameraInfo& msg)
25 {
26  // Distortion model and parameters
27  msg.distortion_model = "plumb_bob";
28  msg.D.resize(5, 0);
29 
30  // Intrinsic camera matrix for the raw (distorted) images.
31  // [fx 0 cx]
32  // K = [ 0 fy cy]
33  // [ 0 0 1]
34  msg.K[0] = cam_model.getFocalLengthX();
35  msg.K[1] = 0;
36  msg.K[2] = cam_model.getOpticalCenterX();
37  msg.K[3] = 0;
38  msg.K[4] = cam_model.getFocalLengthY();
39  msg.K[5] = cam_model.getOpticalCenterY();
40  msg.K[6] = 0;
41  msg.K[7] = 0;
42  msg.K[8] = 1;
43 
44  // Rectification matrix (stereo cameras only)
45  msg.R[0] = 1;
46  msg.R[1] = 0;
47  msg.R[2] = 0;
48  msg.R[3] = 0;
49  msg.R[4] = 1;
50  msg.R[5] = 0;
51  msg.R[6] = 0;
52  msg.R[7] = 0;
53  msg.R[8] = 1;
54 
55  // Projection/camera matrix
56  // [fx' 0 cx' Tx]
57  // P = [ 0 fy' cy' Ty]
58  // [ 0 0 1 0]
59  msg.P[0] = cam_model.getFocalLengthX();
60  msg.P[1] = 0;
61  msg.P[2] = cam_model.getOpticalCenterX();
62  msg.P[3] = cam_model.getOpticalTranslationX();
63  msg.P[4] = 0;
64  msg.P[5] = cam_model.getFocalLengthY();
65  msg.P[6] = cam_model.getOpticalCenterY();
66  msg.P[7] = cam_model.getOpticalTranslationY();
67  msg.P[8] = 0;
68  msg.P[9] = 0;
69  msg.P[10] = 1;
70  msg.P[11] = 0;
71 
72  // TODO: add width and height field to DepthCamera
73  msg.width = cam_model.width();
74  msg.height = cam_model.height();
75 
76  msg.binning_x = 1;
77  msg.binning_y = 1;
78 }
79 
80 } // end geo namespace
geo::DepthCamera::getOpticalCenterY
double getOpticalCenterY() const
Definition: DepthCamera.h:229
geo
Definition: Box.h:6
geo::Mesh::getTriangleIs
const std::vector< TriangleI > & getTriangleIs() const
Definition: Mesh.cpp:46
std::vector
geo::DepthCamera::getOpticalTranslationX
double getOpticalTranslationX() const
Definition: DepthCamera.h:232
geo::Mesh::getPoints
const std::vector< geo::Vector3 > & getPoints() const
Definition: Mesh.cpp:42
geo::DepthCamera::getFocalLengthX
double getFocalLengthX() const
Definition: DepthCamera.h:220
geo::DepthCamera::getOpticalTranslationY
double getOpticalTranslationY() const
Definition: DepthCamera.h:235
geo::DepthCamera::getFocalLengthY
double getFocalLengthY() const
Definition: DepthCamera.h:223
std::vector::begin
T begin(T... args)
geo::convert
void convert(const geo::Vector3 &v, geometry_msgs::Point &msg)
converting geo::Vector3 to geometry_msgs::Point message
Definition: msg_conversions.h:23
geo::DepthCamera
Definition: DepthCamera.h:159
std::vector::end
T end(T... args)
msg_conversions.h
geo::DepthCamera::width
int width() const
Definition: DepthCamera.h:239
geo::DepthCamera::height
int height() const
Definition: DepthCamera.h:237
geo::Mesh
Definition: Mesh.h:25
geo::DepthCamera::getOpticalCenterX
double getOpticalCenterX() const
Definition: DepthCamera.h:226