#include <Kinematics.h>
Classes | |
class | InitFailed |
Public Types | |
enum | FootSupport { SUPPORT_DOUBLE, SUPPORT_SINGLE_RIGHT, SUPPORT_SINGLE_LEFT } |
Public Member Functions | |
void | computeCOM (const JointMap &joint_positions, tf::Point &com, double &mass, tf::Transform &tf_right_foot, tf::Transform &tf_left_foot) |
Kinematics () | |
virtual | ~Kinematics () |
Protected Member Functions | |
void | addChildren (const KDL::SegmentMap::const_iterator segment) |
void | computeCOMRecurs (const KDL::SegmentMap::const_iterator ¤tSeg, const std::map< std::string, double > &joint_positions, const KDL::Frame &tf, KDL::Frame &tf_right_foot, KDL::Frame &tf_left_foot, double &m, KDL::Vector &cog) |
void | createCoGMarker (const std::string &ns, const std::string &frame_id, double radius, const KDL::Vector &cog, visualization_msgs::Marker &marker) const |
bool | loadModel (const std::string xml) |
Protected Attributes | |
KDL::Chain | kdl_chain_left_ |
KDL::Chain | kdl_chain_right_ |
KDL::Tree | kdl_tree_ |
std::string | lfoot_link_name_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_private_ |
unsigned int | num_joints_ |
std::string | rfoot_link_name_ |
std::string | root_link_name_ |
std::map< std::string, robot_state_publisher::SegmentPair > | segments_ |
urdf::Model | urdf_model_ |
Class to compute the center of mass while recursively traversing a kinematic tree of a robot (from URDF)
Definition at line 68 of file Kinematics.h.
Definition at line 70 of file Kinematics.h.
Definition at line 41 of file Kinematics.cpp.
hrl_kinematics::Kinematics::~Kinematics | ( | ) | [virtual] |
Definition at line 66 of file Kinematics.cpp.
void hrl_kinematics::Kinematics::addChildren | ( | const KDL::SegmentMap::const_iterator | segment | ) | [protected] |
Definition at line 100 of file Kinematics.cpp.
void hrl_kinematics::Kinematics::computeCOM | ( | const JointMap & | joint_positions, |
tf::Point & | com, | ||
double & | mass, | ||
tf::Transform & | tf_right_foot, | ||
tf::Transform & | tf_left_foot | ||
) |
Computes the center of mass of the given robot structure and joint configuration. Will also return the 6D transformations to the feet while traversing the robot tree
[in] | joint_positions | angles of all joints |
[out] | com | the computed center of mass in the root coordinate frame (base_link) |
[out] | mass | total mass of all joints |
[out] | tf_right_foot | returned transformation from body reference frame to right foot |
[out] | tf_left_foot | returned transformation from body reference frame to left foot |
Definition at line 186 of file Kinematics.cpp.
void hrl_kinematics::Kinematics::computeCOMRecurs | ( | const KDL::SegmentMap::const_iterator & | currentSeg, |
const std::map< std::string, double > & | joint_positions, | ||
const KDL::Frame & | tf, | ||
KDL::Frame & | tf_right_foot, | ||
KDL::Frame & | tf_left_foot, | ||
double & | m, | ||
KDL::Vector & | cog | ||
) | [protected] |
Definition at line 137 of file Kinematics.cpp.
void hrl_kinematics::Kinematics::createCoGMarker | ( | const std::string & | ns, |
const std::string & | frame_id, | ||
double | radius, | ||
const KDL::Vector & | cog, | ||
visualization_msgs::Marker & | marker | ||
) | const [protected] |
Definition at line 122 of file Kinematics.cpp.
bool hrl_kinematics::Kinematics::loadModel | ( | const std::string | xml | ) | [protected] |
Definition at line 70 of file Kinematics.cpp.
Definition at line 105 of file Kinematics.h.
Definition at line 104 of file Kinematics.h.
KDL::Tree hrl_kinematics::Kinematics::kdl_tree_ [protected] |
Definition at line 103 of file Kinematics.h.
std::string hrl_kinematics::Kinematics::lfoot_link_name_ [protected] |
Definition at line 110 of file Kinematics.h.
ros::NodeHandle hrl_kinematics::Kinematics::nh_ [protected] |
Definition at line 107 of file Kinematics.h.
Definition at line 107 of file Kinematics.h.
unsigned int hrl_kinematics::Kinematics::num_joints_ [protected] |
Definition at line 112 of file Kinematics.h.
std::string hrl_kinematics::Kinematics::rfoot_link_name_ [protected] |
Definition at line 109 of file Kinematics.h.
std::string hrl_kinematics::Kinematics::root_link_name_ [protected] |
Definition at line 108 of file Kinematics.h.
std::map<std::string, robot_state_publisher::SegmentPair> hrl_kinematics::Kinematics::segments_ [protected] |
Definition at line 113 of file Kinematics.h.
urdf::Model hrl_kinematics::Kinematics::urdf_model_ [protected] |
Definition at line 102 of file Kinematics.h.