Skip to content

Commit

Permalink
Fix order of KdlTree::transform arguments.
Browse files Browse the repository at this point in the history
refs #228
  • Loading branch information
de-vri-es committed Jul 29, 2016
1 parent 3c1f15d commit 7478522
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 16 deletions.
20 changes: 10 additions & 10 deletions include/dr_kdl/dr_kdl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,35 +9,35 @@
namespace dr {


/// Get a the transform from the base to the end of a chain.
/// Get a the pose of the end frame relative to the start frame of a chain.
/**
* Throws if a non-fixed joint is encountered in the chain.
* \return The transform from the base of the chain to the end.
*/
Eigen::Isometry3d getTransform(
Eigen::Isometry3d getPose(
KDL::Chain const & chain ///< The chain.
);


/// Get a the transform from the base to the end of a chain.
/// Get a the pose of the end frame relative to the start frame of a chain.
/**
* Non-fixed joints are looked up in a map.
* Throws if a joint is not found.
* \return The transform from the base of the chain to the end.
*/
Eigen::Isometry3d getTransform(
Eigen::Isometry3d getPose(
KDL::Chain const & chain, ///< The chain.
std::map<std::string, double> const & joints ///< The map of joint positions to use for non fixed joints in the chain.
);


/// Get a the transform from the base to the end of a chain.
/// Get a the pose of the end frame relative to the start frame of a chain.
/**
* Non-fixed joints are looked up in a pair of vectors.
* Throws if a joint is not found.
* \return The transform from the base of the chain to the end.
*/
Eigen::Isometry3d getTransform(
Eigen::Isometry3d getPose(
KDL::Chain const & chain, ///< The chain.
std::vector<std::string> const & joint_names, ///< The names of the joints in same order as the joint position vector.
std::vector<double> const & joint_positions ///< The positions of the joints in the same order as the joint name vector.
Expand Down Expand Up @@ -69,7 +69,7 @@ class KdlTree : public KDL::Tree {
std::string const & source, ///< The source frame.
std::string const & target ///< The target frame.
) const {
return getTransform(getChain(source, target));
return getPose(getChain(target, source));
}

/// Get a transform from one frame to another.
Expand All @@ -81,7 +81,7 @@ class KdlTree : public KDL::Tree {
std::string const & target, ///< The target frame.
std::map<std::string, double> const & joints ///< The map holding joint positions.
) const {
return getTransform(getChain(source, target), joints);
return getPose(getChain(target, source), joints);
}

/// Get a transform from one frame to another.
Expand All @@ -94,7 +94,7 @@ class KdlTree : public KDL::Tree {
std::vector<std::string> const & joint_names, ///< The names of the joints in same order as the joint position vector.
std::vector<double> const & joint_positions ///< The positions of the joints in the same order as the joint name vector.
) const {
return getTransform(getChain(source, target), joint_names, joint_positions);
return getPose(getChain(target, source), joint_names, joint_positions);
}

/// Get a transform from one frame to another.
Expand All @@ -106,7 +106,7 @@ class KdlTree : public KDL::Tree {
std::string const & target, ///< The target frame.
sensor_msgs::JointState const & joints ///< The joint positions.
) const {
return getTransform(getChain(source, target), joints.name, joints.position);
return getPose(getChain(target, source), joints.name, joints.position);
}

};
Expand Down
12 changes: 6 additions & 6 deletions src/dr_kdl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ namespace {
}
}

/// Get a the transform from the base to the tip of a chain.
Eigen::Isometry3d getTransform(KDL::Chain const & chain) {
/// Get a the pose of the end frame relative to the start frame of a chain.
Eigen::Isometry3d getPose(KDL::Chain const & chain) {
KDL::Frame transform = KDL::Frame::Identity();
for (auto const & segment : chain.segments) {
// Make sure we're only dealing with fixed joints.
Expand All @@ -47,8 +47,8 @@ Eigen::Isometry3d getTransform(KDL::Chain const & chain) {
return toEigen(transform);
}

/// Get a the transform from the base to the tip of a chain.
Eigen::Isometry3d getTransform(KDL::Chain const & chain, std::map<std::string, double> const & joints) {
/// Get a the pose of the end frame relative to the start frame of a chain.
Eigen::Isometry3d getPose(KDL::Chain const & chain, std::map<std::string, double> const & joints) {
KDL::Frame transform = KDL::Frame::Identity();

for (auto const & segment : chain.segments) {
Expand All @@ -67,8 +67,8 @@ Eigen::Isometry3d getTransform(KDL::Chain const & chain, std::map<std::string, d
return toEigen(transform);
}

/// Get a the transform from the base to the tip of a chain.
Eigen::Isometry3d getTransform(KDL::Chain const & chain, std::vector<std::string> const & joint_names, std::vector<double> const & joint_positions) {
/// Get a the pose of the end frame relative to the start frame of a chain.
Eigen::Isometry3d getPose(KDL::Chain const & chain, std::vector<std::string> const & joint_names, std::vector<double> const & joint_positions) {
KDL::Frame transform = KDL::Frame::Identity();

for (auto const & segment : chain.segments) {
Expand Down

0 comments on commit 7478522

Please sign in to comment.