InverseDynamicsSolverKDL.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /*
00036   Author: Daniel Hennes
00037  */
00038 
00039 #include <iostream>
00040 #include <sstream>
00041 #include <vector>
00042 
00043 #include <ros/ros.h>
00044 #include <kdl_parser/kdl_parser.hpp>
00045 #include <kdl/chain.hpp>
00046 #include <kdl/chainidsolver_recursive_newton_euler.hpp>
00047 
00048 int main( int argc, char** argv )
00049 {
00050   ros::init(argc, argv, "kdl_dynamics");
00051 
00052   KDL::Tree kdl_tree;
00053   ros::NodeHandle node;
00054   std::string robot_desc_string;
00055   node.param("robot_description", robot_desc_string, std::string());
00056   if (!kdl_parser::treeFromString(robot_desc_string, kdl_tree)){
00057     ROS_ERROR("Failed to construct KDL tree.");
00058     exit(-1);
00059   }
00060 
00061   // std::cout << kdl_tree.getNrOfJoints() << std::endl;
00062   // KDL::SegmentMap kdl_segments = kdl_tree.getSegments();
00063   // for (KDL::SegmentMap::iterator it = kdl_segments.begin(); 
00064   //      it != kdl_segments.end(); 
00065   //      ++it) {
00066   //   std::cout << (*it).first << std::endl;
00067   // }
00068 
00069   KDL::Chain kdl_chain;
00070   if (!kdl_tree.getChain("torso_lift_link", "r_wrist_roll_link", kdl_chain)) {
00071     ROS_ERROR("Failed to get chain from KDL tree.");
00072     exit(-1);
00073   }
00074 
00075   KDL::Vector grav;
00076   KDL::ChainIdSolver_RNE kdl_idsolver(kdl_chain, grav);
00077   
00078   std::istream * in;
00079   in = &std::cin;
00080   
00081   const size_t ndof(kdl_chain.getNrOfJoints());
00082   const size_t nstate(3 * ndof);
00083 
00084   int status = 0;
00085 
00086   for (size_t lineno(1); *in; ++lineno) {
00087     std::string line;
00088     getline(*in, line);
00089 
00090     std::vector<double> state;
00091     std::istringstream ls(line);
00092     double value;
00093     while (ls >> value) {
00094       state.push_back(value);
00095     }
00096 
00097     // end of file or input
00098     if (0 == state.size()) {
00099       break;
00100     }
00101 
00102     // check if input dimensions agree
00103     if (nstate != state.size()) {
00104       ROS_ERROR("expected %zu DOF, but read line with %zu (!=%zu) doubles!", ndof, state.size(), nstate);
00105       break;
00106     }
00107 
00108     // compute torques
00109     KDL::JntArray q = KDL::JntArray(ndof);
00110     KDL::JntArray q_dot = KDL::JntArray(ndof);
00111     KDL::JntArray q_dotdot = KDL::JntArray(ndof);
00112     KDL::JntArray torques = KDL::JntArray(ndof);
00113     KDL::Wrenches f_ext;
00114     f_ext.resize(ndof);
00115 
00116     status = kdl_idsolver.CartToJnt(q, q_dot, q_dotdot, f_ext, torques);
00117     if (status < 0)
00118       ROS_ERROR("KDL inverse dynamics solver returned: %d", status);
00119 
00120     for (uint i = 0; i < ndof; i++) {
00121       std::cout << torques(i) << " ";
00122     }
00123     std::cout << std::endl;
00124  
00125   }
00126 
00127 }


kelsey_sandbox
Author(s): kelsey
autogenerated on Wed Nov 27 2013 11:52:04