28 const sensor_msgs::JointState& msg)
30 for (
size_t i = 0; i < msg.name.size(); ++i)
32 if (msg.name[i] ==
name)
33 return msg.position[i];
36 std::cerr <<
"Unable to find " <<
name <<
" in sensor_msgs::JointState" << std::endl;
42 root_(root), tip_(tip), name_(
name)
45 if (!model.getChain(root, tip,
chain_))
47 auto error_msg = std::string{
"Failed to build a chain model from "} + root +
" to " + tip +
", check the link names";
49 throw std::runtime_error(error_msg);
54 const robot_calibration_msgs::CalibrationData& data,
58 std::vector<geometry_msgs::PointStamped> points;
62 for (
size_t obs = 0; obs < data.observations.size(); obs++)
64 if (data.observations[obs].sensor_name ==
name_)
78 points.resize(data.observations[sensor_idx].features.size());
81 KDL::Frame fk =
getChainFK(offsets, data.joint_states);
84 for (
size_t i = 0; i < points.size(); ++i)
86 points[i].header.frame_id =
root_;
88 KDL::Frame p(KDL::Frame::Identity());
89 p.p.x(data.observations[sensor_idx].features[i].point.x);
90 p.p.y(data.observations[sensor_idx].features[i].point.y);
91 p.p.z(data.observations[sensor_idx].features[i].point.z);
96 if (data.observations[sensor_idx].features[i].header.frame_id !=
tip_)
98 KDL::Frame p2(KDL::Frame::Identity());
99 if (offsets.
getFrame(data.observations[sensor_idx].features[i].header.frame_id, p2))
109 points[i].point.x = p.p.x();
110 points[i].point.y = p.p.y();
111 points[i].point.z = p.p.z();
118 const sensor_msgs::JointState& state)
121 KDL::Frame p_out = KDL::Frame::Identity();
124 for (
size_t i = 0; i <
chain_.getNrOfSegments(); ++i)
126 std::string
name =
chain_.getSegment(i).getJoint().getName();
127 KDL::Frame correction = KDL::Frame::Identity();
131 if (
chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
135 pose =
chain_.getSegment(i).pose(p);
139 pose =
chain_.getSegment(i).pose(0.0);
142 KDL::Frame totip =
chain_.getSegment(i).getFrameToTip();
145 p_out = p_out * KDL::Frame(pose.p + totip.M * correction.p);
146 p_out = p_out * KDL::Frame(totip.M * correction.M * totip.M.Inverse() * pose.M);
164 param_name_(param_name)
170 const robot_calibration_msgs::CalibrationData& data,
173 std::vector<geometry_msgs::PointStamped> points;
177 for (
size_t obs = 0; obs < data.observations.size(); obs++)
179 if (data.observations[obs].sensor_name ==
name_)
193 if (data.observations[sensor_idx].ext_camera_info.camera_info.P.size() != 12)
194 std::cerr <<
"Unexpected CameraInfo projection matrix size" << std::endl;
206 double z_offset = 0.0;
207 double z_scaling = 1.0;
208 for (
size_t i = 0; i < data.observations[sensor_idx].ext_camera_info.parameters.size(); i++)
210 if (data.observations[sensor_idx].ext_camera_info.parameters[i].name ==
"z_scaling")
212 z_scaling = data.observations[sensor_idx].ext_camera_info.parameters[i].value;
214 else if (data.observations[sensor_idx].ext_camera_info.parameters[i].name ==
"z_offset_mm")
216 z_offset = data.observations[sensor_idx].ext_camera_info.parameters[i].value / 1000.0;
221 double new_camera_fx = camera_fx * (1.0 + offsets.
get(
param_name_ +
"_fx"));
222 double new_camera_fy = camera_fy * (1.0 + offsets.
get(
param_name_ +
"_fy"));
223 double new_camera_cx = camera_cx * (1.0 + offsets.
get(
param_name_ +
"_cx"));
224 double new_camera_cy = camera_cy * (1.0 + offsets.
get(
param_name_ +
"_cy"));
226 double new_z_scaling = 1.0 + offsets.
get(
param_name_ +
"_z_scaling");
228 points.resize(data.observations[sensor_idx].features.size());
231 KDL::Frame fk =
getChainFK(offsets, data.joint_states);
233 for (
size_t i = 0; i < points.size(); ++i)
236 double x = data.observations[sensor_idx].features[i].point.x;
237 double y = data.observations[sensor_idx].features[i].point.y;
238 double z = data.observations[sensor_idx].features[i].point.z;
241 double u =
x * camera_fx /
z + camera_cx;
242 double v =
y * camera_fy /
z + camera_cy;
243 double depth =
z/z_scaling - z_offset;
245 KDL::Frame pt(KDL::Frame::Identity());
248 pt.p.z((depth + new_z_offset) * new_z_scaling);
249 pt.p.x((u - new_camera_cx) * pt.p.z() / new_camera_fx);
250 pt.p.y((v - new_camera_cy) * pt.p.z() / new_camera_fy);
255 points[i].point.x = pt.p.x();
256 points[i].point.y = pt.p.y();
257 points[i].point.z = pt.p.z();
258 points[i].header.frame_id =
root_;
266 return "Camera3dModel";
271 double magnitude = sqrt(
x*
x +
y*
y +
z*
z);
273 if (magnitude == 0.0)
274 return KDL::Rotation::Quaternion(0.0, 0.0, 0.0, 1.0);
276 return KDL::Rotation::Quaternion(
x/magnitude * sin(magnitude/2.0),
277 y/magnitude * sin(magnitude/2.0),
278 z/magnitude * sin(magnitude/2.0),
284 double qx, qy, qz, qw;
285 r.GetQuaternion(qx, qy, qz, qw);
293 double magnitude = 2 * acos(qw);
294 double k = sqrt(1 - (qw*qw));
296 x = (qx / k) * magnitude;
297 y = (qy / k) * magnitude;
298 z = (qz / k) * magnitude;