models.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Fetch Robotics Inc.
3  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  */
17 
18 // Author: Michael Ferguson
19 
22 
23 namespace robot_calibration
24 {
25 
26 double positionFromMsg(const std::string& name,
27  const sensor_msgs::JointState& msg)
28 {
29  for (size_t i = 0; i < msg.name.size(); ++i)
30  {
31  if (msg.name[i] == name)
32  return msg.position[i];
33  }
34 
35  std::cerr << "Unable to find " << name << " in sensor_msgs::JointState" << std::endl;
36 
37  return 0.0;
38 }
39 
40 ChainModel::ChainModel(const std::string& name, KDL::Tree model, std::string root, std::string tip) :
41  root_(root), tip_(tip), name_(name)
42 {
43  // Create a KDL::Chain
44  if (!model.getChain(root, tip, chain_))
45  std::cerr << "Failed to get chain" << std::endl;
46 }
47 
48 std::vector<geometry_msgs::PointStamped> ChainModel::project(
49  const robot_calibration_msgs::CalibrationData& data,
50  const CalibrationOffsetParser& offsets)
51 {
52  // Projected points, to be returned
53  std::vector<geometry_msgs::PointStamped> points;
54 
55  // Determine which observation to use
56  int sensor_idx = -1;
57  for (size_t obs = 0; obs < data.observations.size(); obs++)
58  {
59  if (data.observations[obs].sensor_name == name_)
60  {
61  sensor_idx = obs;
62  break;
63  }
64  }
65 
66  if (sensor_idx < 0)
67  {
68  // TODO: any sort of error message?
69  return points;
70  }
71 
72  // Resize to match # of features
73  points.resize(data.observations[sensor_idx].features.size());
74 
75  // Get the projection from forward kinematics of the robot chain
76  KDL::Frame fk = getChainFK(offsets, data.joint_states);
77 
78  // Project each individual point
79  for (size_t i = 0; i < points.size(); ++i)
80  {
81  points[i].header.frame_id = root_; // fk returns point in root_ frame
82 
84  p.p.x(data.observations[sensor_idx].features[i].point.x);
85  p.p.y(data.observations[sensor_idx].features[i].point.y);
86  p.p.z(data.observations[sensor_idx].features[i].point.z);
87 
88  // This is primarily for the case of checkerboards
89  // The observation is in "checkerboard" frame, but the tip of the
90  // kinematic chain is typically something like "wrist_roll_link".
91  if (data.observations[sensor_idx].features[i].header.frame_id != tip_)
92  {
94  if (offsets.getFrame(data.observations[sensor_idx].features[i].header.frame_id, p2))
95  {
96  // We have to apply the frame offset before the FK projection
97  p = p2 * p;
98  }
99  }
100 
101  // Apply the FK projection
102  p = fk * p;
103 
104  points[i].point.x = p.p.x();
105  points[i].point.y = p.p.y();
106  points[i].point.z = p.p.z();
107  }
108 
109  return points;
110 }
111 
113  const sensor_msgs::JointState& state)
114 {
115  // FK from root to tip
117 
118  // Step through joints
119  for (size_t i = 0; i < chain_.getNrOfSegments(); ++i)
120  {
121  std::string name = chain_.getSegment(i).getJoint().getName();
122  KDL::Frame correction = KDL::Frame::Identity();
123  offsets.getFrame(name, correction);
124 
125  KDL::Frame pose;
127  {
128  // Apply any joint offset calibration
129  double p = positionFromMsg(name, state) + offsets.get(name);
130  pose = chain_.getSegment(i).pose(p);
131  }
132  else
133  {
134  pose = chain_.getSegment(i).pose(0.0);
135  }
136 
138 
139  // Apply any frame calibration on the joint <origin> frame
140  p_out = p_out * KDL::Frame(pose.p + totip.M * correction.p);
141  p_out = p_out * KDL::Frame(totip.M * correction.M * totip.M.Inverse() * pose.M);
142 
143  }
144  return p_out;
145 }
146 
147 Camera3dModel::Camera3dModel(const std::string& name, KDL::Tree model, std::string root, std::string tip) :
148  ChainModel(name, model, root, tip)
149 {
150  // TODO add additional parameters for unprojecting observations using initial parameters
151 }
152 
153 std::vector<geometry_msgs::PointStamped> Camera3dModel::project(
154  const robot_calibration_msgs::CalibrationData& data,
155  const CalibrationOffsetParser& offsets)
156 {
157  std::vector<geometry_msgs::PointStamped> points;
158 
159  // Determine which observation to use
160  int sensor_idx = -1;
161  for (size_t obs = 0; obs < data.observations.size(); obs++)
162  {
163  if (data.observations[obs].sensor_name == name_)
164  {
165  sensor_idx = obs;
166  break;
167  }
168  }
169 
170  if (sensor_idx < 0)
171  {
172  // TODO: any sort of error message?
173  return points;
174  }
175 
176  // Get existing camera info
177  if (data.observations[sensor_idx].ext_camera_info.camera_info.P.size() != 12)
178  std::cerr << "Unexpected CameraInfo projection matrix size" << std::endl;
179 
180  double camera_fx = data.observations[sensor_idx].ext_camera_info.camera_info.P[CAMERA_INFO_P_FX_INDEX];
181  double camera_fy = data.observations[sensor_idx].ext_camera_info.camera_info.P[CAMERA_INFO_P_FY_INDEX];
182  double camera_cx = data.observations[sensor_idx].ext_camera_info.camera_info.P[CAMERA_INFO_P_CX_INDEX];
183  double camera_cy = data.observations[sensor_idx].ext_camera_info.camera_info.P[CAMERA_INFO_P_CY_INDEX];
184 
185  /*
186  * z_scale and z_offset defined in openni2_camera/src/openni2_driver.cpp
187  * new_depth_mm = (depth_mm + z_offset_mm) * z_scale
188  * NOTE: these work on integer values not floats
189  */
190  double z_offset = 0.0;
191  double z_scaling = 1.0;
192  for (size_t i = 0; i < data.observations[sensor_idx].ext_camera_info.parameters.size(); i++)
193  {
194  if (data.observations[sensor_idx].ext_camera_info.parameters[i].name == "z_scaling")
195  {
196  z_scaling = data.observations[sensor_idx].ext_camera_info.parameters[i].value;
197  }
198  else if (data.observations[sensor_idx].ext_camera_info.parameters[i].name == "z_offset_mm")
199  {
200  z_offset = data.observations[sensor_idx].ext_camera_info.parameters[i].value / 1000.0; // (mm -> m)
201  }
202  }
203 
204  // Get calibrated camera info
205  double new_camera_fx = camera_fx * (1.0 + offsets.get(name_+"_fx"));
206  double new_camera_fy = camera_fy * (1.0 + offsets.get(name_+"_fy"));
207  double new_camera_cx = camera_cx * (1.0 + offsets.get(name_+"_cx"));
208  double new_camera_cy = camera_cy * (1.0 + offsets.get(name_+"_cy"));
209  double new_z_offset = offsets.get(name_+"_z_offset");
210  double new_z_scaling = 1.0 + offsets.get(name_+"_z_scaling");
211 
212  points.resize(data.observations[sensor_idx].features.size());
213 
214  // Get position of camera frame
215  KDL::Frame fk = getChainFK(offsets, data.joint_states);
216 
217  for (size_t i = 0; i < points.size(); ++i)
218  {
219  // TODO: warn if frame_id != tip?
220  double x = data.observations[sensor_idx].features[i].point.x;
221  double y = data.observations[sensor_idx].features[i].point.y;
222  double z = data.observations[sensor_idx].features[i].point.z;
223 
224  // Unproject through parameters stored at runtime
225  double u = x * camera_fx / z + camera_cx;
226  double v = y * camera_fy / z + camera_cy;
227  double depth = z/z_scaling - z_offset;
228 
230 
231  // Reproject through new calibrated parameters
232  pt.p.z((depth + new_z_offset) * new_z_scaling);
233  pt.p.x((u - new_camera_cx) * pt.p.z() / new_camera_fx);
234  pt.p.y((v - new_camera_cy) * pt.p.z() / new_camera_fy);
235 
236  // Project through fk
237  pt = fk * pt;
238 
239  points[i].point.x = pt.p.x();
240  points[i].point.y = pt.p.y();
241  points[i].point.z = pt.p.z();
242  points[i].header.frame_id = root_;
243  }
244 
245  return points;
246 }
247 
248 KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z)
249 {
250  double magnitude = sqrt(x*x + y*y + z*z);
251 
252  if (magnitude == 0.0)
253  return KDL::Rotation::Quaternion(0.0, 0.0, 0.0, 1.0);
254 
255  return KDL::Rotation::Quaternion(x/magnitude * sin(magnitude/2.0),
256  y/magnitude * sin(magnitude/2.0),
257  z/magnitude * sin(magnitude/2.0),
258  cos(magnitude/2.0));
259 }
260 
261 void axis_magnitude_from_rotation(const KDL::Rotation& r, double& x, double& y, double& z)
262 {
263  double qx, qy, qz, qw;
264  r.GetQuaternion(qx, qy, qz, qw);
265 
266  if (qw == 1.0)
267  {
268  x = y = z = 0.0;
269  return;
270  }
271 
272  double magnitude = 2 * acos(qw);
273  double k = sqrt(1 - (qw*qw));
274 
275  x = (qx / k) * magnitude;
276  y = (qy / k) * magnitude;
277  z = (qz / k) * magnitude;
278 }
279 
280 } // namespace robot_calibration
virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the position of the estimated points.
Definition: models.cpp:48
const Segment & getSegment(unsigned int nr) const
Rotation Inverse() const
bool getFrame(const std::string name, KDL::Frame &offset) const
Get the offset for a frame calibration.
unsigned int getNrOfSegments() const
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
static Rotation Quaternion(double x, double y, double z, double w)
Frame getFrameToTip() const
Camera3dModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)
Create a new camera 3d model (Kinect/Primesense).
Definition: models.cpp:147
ChainModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)
Create a new chain model.
Definition: models.cpp:40
TFSIMD_FORCE_INLINE const tfScalar & y() const
KDL::Frame getChainFK(const CalibrationOffsetParser &offsets, const sensor_msgs::JointState &state)
Compute the forward kinematics of the chain, based on the offsets and the joint positions of the stat...
Definition: models.cpp:112
double z() const
Rotation M
Frame pose(const double &q) const
void GetQuaternion(double &x, double &y, double &z, double &w) const
const std::string & getName() const
double y() const
double x() const
const Joint & getJoint() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
Calibration code lives under this namespace.
double get(const std::string name) const
Get the offset.
void axis_magnitude_from_rotation(const KDL::Rotation &r, double &x, double &y, double &z)
Converts from KDL::Rotation to angle-axis-with-integrated-magnitude.
Definition: models.cpp:261
KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z)
Converts our angle-axis-with-integrated-magnitude representation to a KDL::Rotation.
Definition: models.cpp:248
TFSIMD_FORCE_INLINE const tfScalar & z() const
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
static Frame Identity()
virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the updated positions of the observed points.
Definition: models.cpp:153
std::string name() const
Definition: chain.h:153
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
Definition: chain.h:107
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
double positionFromMsg(const std::string &name, const sensor_msgs::JointState &msg)
Definition: models.cpp:26
const JointType & getType() const


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30