00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 // Author: Stuart Glaser 00031 00032 #ifndef MECHANISM_MODEL_CHAIN_H 00033 #define MECHANISM_MODEL_CHAIN_H 00034 00035 #include "pr2_mechanism_model/robot.h" 00036 #include <kdl/chain.hpp> 00037 #include <kdl/jntarray.hpp> 00038 #include <kdl/jntarrayvel.hpp> 00039 #include <kdl/jntarrayacc.hpp> 00040 00041 namespace pr2_mechanism_model { 00042 00043 class Chain 00044 { 00045 public: 00046 Chain() {} 00047 ~Chain() {} 00048 00056 bool init(RobotState *robot_state, const std::string &root, const std::string &tip); 00057 00059 void getPositions(std::vector<double>&); 00061 void getPositions(KDL::JntArray&); 00063 template <class Vec> 00064 void getPositions(Vec &v) 00065 { 00066 assert((int)v.size() == (int)joints_.size()); 00067 for (size_t i = 0; i < joints_.size(); ++i) 00068 v[i] = joints_[i]->position_; 00069 } 00070 00072 void getVelocities(std::vector<double>&); 00074 void getVelocities(KDL::JntArrayVel&); 00076 template <class Vec> 00077 void getVelocities(Vec &v) 00078 { 00079 assert((int)v.size() == (int)joints_.size()); 00080 for (size_t i = 0; i < joints_.size(); ++i) 00081 v[i] = joints_[i]->velocity_; 00082 } 00083 00084 00086 void getEfforts(std::vector<double>&); 00088 void getEfforts(KDL::JntArray&); 00089 00091 void setEfforts(KDL::JntArray&); 00093 void addEfforts(KDL::JntArray&); 00094 00098 template <class Vec> 00099 void addEfforts(const Vec& v) 00100 { 00101 assert((int)v.size() == (int)joints_.size()); 00102 for (size_t i = 0; i < joints_.size(); ++i) 00103 joints_[i]->commanded_effort_ += v[i]; 00104 } 00105 00107 bool allCalibrated(); 00108 00110 void toKDL(KDL::Chain &chain); 00111 00117 JointState* getJoint(unsigned int actuated_joint_i); 00118 00120 int size() const { return joints_.size(); } 00121 00122 private: 00123 pr2_mechanism_model::RobotState *robot_state_; 00124 KDL::Chain kdl_chain_; 00125 00126 std::vector< JointState* > joints_; // ONLY joints that can be actuated (not fixed joints) 00127 }; 00128 00129 } 00130 00131 #endif