1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 18:10:47 +02:00

Cleaned up legacy code and updated documentation.

This commit is contained in:
Felix Mauch
2019-05-29 08:52:39 +02:00
parent a603e9bb97
commit 6adda40a3f
2 changed files with 49 additions and 75 deletions

View File

@@ -101,26 +101,6 @@ struct DHRobot
}
return ret;
}
/*!
* \brief Generates a string representation of this robot representation.
*
* This string can be directly included into the xacro file used for a calibrated robot.
*/
std::string toXacroProperties()
{
std::stringstream ss;
for (size_t i = 0; i < segments_.size(); ++i)
{
ss << "<xacro:property name=\"d" << i + 1 << "\" value=\"" << segments_[i].d_ << "\" />\n";
ss << "<xacro:property name=\"a" << i + 1 << "\" value=\"" << segments_[i].a_ << "\" />\n";
ss << "<xacro:property name=\"theta" << i + 1 << "\" value=\"" << segments_[i].theta_ << "\" />\n";
ss << "<xacro:property name=\"alpha" << i + 1 << "\" value=\"" << segments_[i].alpha_ << "\" />\n";
}
ss << "<xacro:property name=\"delta_theta_correction2\" value=\"" << delta_theta_correction2_ << "\" />\n";
ss << "<xacro:property name=\"delta_theta_correction3\" value=\"" << delta_theta_correction3_ << "\" />\n";
return ss.str();
}
};
/*!
@@ -145,28 +125,59 @@ public:
*/
void correctChain();
/*!
* \brief Get the transformation matrix representation of the chain as constructed by the
* DH parameters.
*
* This will contain twice as many transformation matrices as joints, as for each set of DH
* parameters two matrices are generated. If you'd like to receive one matrix per joint instead,
* use the getSimplified() function instead.
*
* \returns A vector of 4x4 transformation matrices, two for each joint going from the base to the
* tcp.
*/
std::vector<Eigen::Matrix4d> getChain()
{
return chain_;
}
std::string toXacroProperties()
{
return robot_parameters_corrected_.toXacroProperties();
}
YAML::Node toYaml() const;
/*!
* \brief Get the transformation matrix representation of the chain, where each joint is
* represented by one matrix.
*
* \returns Vector of 4x4 transformation matrices, one for each joint going from the base to the
* tcp.
*/
std::vector<Eigen::Matrix4d> getSimplified() const;
/*!
* \brief Generates a yaml representation of all transformation matrices as returned by
* getSimplified()
*
* \returns A YAML tree representing all tranformation matrices.
*/
YAML::Node toYaml() const;
/*!
* \brief Calculates the forwart kinematics given a joint configuration with respect to the base
* link.
*
* \param joint_values Joint values for which the forward kinematics should be calculated.
* \param link_nr If given, the cartesian position for this joint (starting at 1) is returned. By
* default the 6th joint is used.
*
* \returns Transformation matrix giving the full pose of the requested link in base coordinates.
*/
Eigen::Matrix4d calcForwardKinematics(const Eigen::Matrix<double, 6, 1>& joint_values, const size_t link_nr = 6);
private:
// Corrects a single axis
void correctAxis(const size_t correction_index);
// Builds the chain from robot_parameters_
void buildChain();
DHRobot robot_parameters_;
DHRobot robot_parameters_corrected_;
std::vector<std::string> link_names_ = { "shoulder", "upper_arm", "forearm", "wrist_1", "wrist_2", "wrist_3" };
std::vector<Eigen::Matrix4d> chain_;