27 const sensor_msgs::JointState& msg)
29 for (
size_t i = 0; i < msg.name.size(); ++i)
31 if (msg.name[i] == name)
32 return msg.position[i];
35 std::cerr <<
"Unable to find " << name <<
" in sensor_msgs::JointState" << std::endl;
41 root_(root), tip_(tip), name_(name)
45 std::cerr <<
"Failed to get chain" << std::endl;
49 const robot_calibration_msgs::CalibrationData& data,
53 std::vector<geometry_msgs::PointStamped> points;
57 for (
size_t obs = 0; obs < data.observations.size(); obs++)
59 if (data.observations[obs].sensor_name ==
name_)
73 points.resize(data.observations[sensor_idx].features.size());
79 for (
size_t i = 0; i < points.size(); ++i)
81 points[i].header.frame_id =
root_;
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);
91 if (data.observations[sensor_idx].features[i].header.frame_id !=
tip_)
94 if (offsets.
getFrame(data.observations[sensor_idx].features[i].header.frame_id, p2))
104 points[i].point.x = p.
p.
x();
105 points[i].point.y = p.p.y();
106 points[i].point.z = p.p.z();
113 const sensor_msgs::JointState& state)
141 p_out = p_out * KDL::Frame(totip.
M * correction.
M * totip.
M.
Inverse() * pose.
M);
154 const robot_calibration_msgs::CalibrationData& data,
157 std::vector<geometry_msgs::PointStamped> points;
161 for (
size_t obs = 0; obs < data.observations.size(); obs++)
163 if (data.observations[obs].sensor_name ==
name_)
177 if (data.observations[sensor_idx].ext_camera_info.camera_info.P.size() != 12)
178 std::cerr <<
"Unexpected CameraInfo projection matrix size" << std::endl;
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++)
194 if (data.observations[sensor_idx].ext_camera_info.parameters[i].name ==
"z_scaling")
196 z_scaling = data.observations[sensor_idx].ext_camera_info.parameters[i].value;
198 else if (data.observations[sensor_idx].ext_camera_info.parameters[i].name ==
"z_offset_mm")
200 z_offset = data.observations[sensor_idx].ext_camera_info.parameters[i].value / 1000.0;
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");
212 points.resize(data.observations[sensor_idx].features.size());
217 for (
size_t i = 0; i < points.size(); ++i)
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;
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;
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);
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_;
250 double magnitude =
sqrt(x*x + y*y + z*z);
252 if (magnitude == 0.0)
256 y/magnitude *
sin(magnitude/2.0),
257 z/magnitude *
sin(magnitude/2.0),
263 double qx, qy, qz, qw;
272 double magnitude = 2 *
acos(qw);
273 double k =
sqrt(1 - (qw*qw));
275 x = (qx / k) * magnitude;
276 y = (qy / k) * magnitude;
277 z = (qz / k) * magnitude;
virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the position of the estimated points.
const Segment & getSegment(unsigned int nr) 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).
ChainModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)
Create a new chain model.
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...
Frame pose(const double &q) const
void GetQuaternion(double &x, double &y, double &z, double &w) const
const std::string & getName() 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.
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.
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)
virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the updated positions of the observed points.
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...
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
double positionFromMsg(const std::string &name, const sensor_msgs::JointState &msg)
const JointType & getType() const