Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef ROS_ETHERCAT_MODEL_TREE_H
00040 #define ROS_ETHERCAT_MODEL_TREE_H
00041
00042 #include <ros/ros.h>
00043 #include <kdl/chain.hpp>
00044 #include <kdl/tree.hpp>
00045 #include <kdl/jntarray.hpp>
00046 #include <kdl/jntarrayvel.hpp>
00047 #include "ros_ethercat_model/robot_state.hpp"
00048 #include <kdl_parser/kdl_parser.hpp>
00049
00050 namespace ros_ethercat_model
00051 {
00052
00053 class Tree
00054 {
00055 public:
00056 Tree() :
00057 kdl_tree_()
00058 {
00059 }
00069 bool init(RobotState *robot_state)
00070 {
00071 KDL::SegmentMap segmentMap;
00072
00073
00074 if (!kdl_parser::treeFromUrdfModel(robot_state->robot_model_, kdl_tree_))
00075 {
00076 ROS_ERROR("Failed to construct KDL:Tree from robot_state's URDF model! Aborting ...");
00077 }
00078 else
00079 {
00080 ROS_INFO("KDL::Tree successful created.");
00081
00082 segmentMap = kdl_tree_.getSegments();
00083 }
00084
00085
00086
00087
00088
00089 std::map<unsigned int, std::string> jointMap;
00090
00091 ROS_DEBUG("Extracting all joints from the tree, which are not of type KDL::Joint::None.");
00092 for (KDL::SegmentMap::const_iterator seg_it = segmentMap.begin(); seg_it != segmentMap.end();
00093 ++seg_it)
00094 {
00095 if (seg_it->second.segment.getJoint().getType() != KDL::Joint::None)
00096 jointMap[seg_it->second.q_nr] = seg_it->second.segment.getJoint().getName().c_str();
00097 }
00098
00099
00100 ROS_DEBUG("Checking, if extracted joints can be found in the JointState vector of the robot.");
00101 joints_.clear();
00102 for (std::map<unsigned int, std::string>::const_iterator jnt_it = jointMap.begin();
00103 jnt_it != jointMap.end(); ++jnt_it)
00104 {
00105 JointState* jnt = robot_state->getJointState(jnt_it->second.c_str());
00106 if (!jnt)
00107 {
00108 ROS_ERROR("Joint '%s' has not been found in the robot's joint state vector! Aborting ...",
00109 jnt_it->second.c_str());
00110 return false;
00111 }
00112 joints_.push_back(jnt);
00113 }
00114
00115 ROS_DEBUG("The result after joint extraction and checking:");
00116 for (unsigned int i = 0; i < joints_.size(); ++i)
00117 {
00118 ROS_DEBUG("joints_[%d]: joint_.name = %s", i, joints_[i]->joint_->name.c_str());
00119 }
00120
00121 ROS_INFO("Added %i joints", int(joints_.size()));
00122
00123 return true;
00124 }
00125
00127 void getPositions(KDL::JntArray& positions) const
00128 {
00129 assert(positions.rows() == joints_.size());
00130 for (unsigned int i = 0; i < joints_.size(); ++i)
00131 positions(i) = joints_[i]->position_;
00132 }
00133
00135 template<class Vec>
00136 void getPositions(Vec &v) const
00137 {
00138 assert((int) v.size() == (int) joints_.size());
00139 for (size_t i = 0; i < joints_.size(); ++i)
00140 v[i] = joints_[i]->position_;
00141 }
00142
00144 void getVelocities(KDL::JntArrayVel &velocities) const
00145 {
00146 assert(velocities.q.rows() == joints_.size());
00147 assert(velocities.qdot.rows() == joints_.size());
00148 for (unsigned int i = 0; i < joints_.size(); ++i)
00149 {
00150 velocities.q(i) = joints_[i]->position_;
00151 velocities.qdot(i) = joints_[i]->velocity_;
00152 }
00153 }
00154
00156 template<class Vec>
00157 void getVelocities(Vec &v) const
00158 {
00159 assert((int) v.size() == (int) joints_.size());
00160 for (size_t i = 0; i < joints_.size(); ++i)
00161 v[i] = joints_[i]->velocity_;
00162 }
00163
00165 void getEfforts(KDL::JntArray &efforts) const
00166 {
00167 assert(efforts.rows() == joints_.size());
00168 for (unsigned int i = 0; i < joints_.size(); ++i)
00169 efforts(i) = joints_[i]->measured_effort_;
00170 }
00171
00173 template<class Vec>
00174 void getEfforts(Vec &v) const
00175 {
00176 assert((int) v.size() == (int) joints_.size());
00177 for (size_t i = 0; i < joints_.size(); ++i)
00178 v[i] = joints_[i]->measured_effort_;
00179 }
00180
00182 void setEfforts(const KDL::JntArray &efforts)
00183 {
00184 assert(efforts.rows() == joints_.size());
00185 for (unsigned int i = 0; i < joints_.size(); ++i)
00186 joints_[i]->commanded_effort_ = efforts(i);
00187 }
00188
00190 template<class Vec>
00191 void setEfforts(const Vec &v)
00192 {
00193 assert((int) v.size() == (int) joints_.size());
00194 for (size_t i = 0; i < joints_.size(); ++i)
00195 joints_[i]->commanded_effort_ = v[i];
00196 }
00197
00199 void addEfforts(const KDL::JntArray &efforts)
00200 {
00201 assert(efforts.rows() == joints_.size());
00202 for (unsigned int i = 0; i < joints_.size(); ++i)
00203 joints_[i]->commanded_effort_ += efforts(i);
00204 }
00205
00207 template<class Vec>
00208 void addEfforts(const Vec &v)
00209 {
00210 assert((int) v.size() == (int) joints_.size());
00211 for (size_t i = 0; i < joints_.size(); ++i)
00212 joints_[i]->commanded_effort_ += v[i];
00213 }
00214
00216 bool allCalibrated() const
00217 {
00218 for (unsigned int i = 0; i < joints_.size(); ++i)
00219 if (!joints_[i]->calibrated_)
00220 return false;
00221 return true;
00222 }
00223
00225 void toKdl(KDL::Tree &tree) const
00226 {
00227 tree = kdl_tree_;
00228 }
00229
00231 JointState* getJoint(unsigned int actuated_joint_i) const
00232 {
00233 if (actuated_joint_i >= joints_.size())
00234 return NULL;
00235 else
00236 return joints_[actuated_joint_i];
00237 }
00238
00240 int size() const
00241 {
00242 return joints_.size();
00243 }
00244
00245 private:
00246 KDL::Tree kdl_tree_;
00248 std::vector<JointState*> joints_;
00249 };
00250
00251 }
00252
00253 #endif