return false;
}
- if (!kdl_parser::treeFromString(robot_desc_string,tree))
+ if (!kdl_parser::treeFromString(robot_desc_string,tree_))
{
ROS_ERROR("Failed to construct KDL tree.");
return false;
return false;
}
- if (!tree.getChain(chainRoot,chainTip,chain))
+ if (!tree_.getChain(chainRoot,chainTip,chain_))
{
ROS_ERROR("Failed to get chain from KDL tree.");
return false;
node_.param("gravity/y",g[1],0.0);
node_.param("gravity/z",g[2],-9.8);
- if((chainParam_=new KDL::ChainDynParam(chain,g)) == NULL)
+ if((chainParam_=new KDL::ChainDynParam(chain_,g)) == NULL)
{
ROS_ERROR("Failed to create ChainDynParam.");
return false;
}
- q_.resize(chain.getNrOfJoints());
- qr_.resize(chain.getNrOfJoints());
- gravity_.resize(chain.getNrOfJoints());
+ q_.resize(chain_.getNrOfJoints());
+ qr_.resize(chain_.getNrOfJoints());
+ gravity_.resize(chain_.getNrOfJoints());
return true;
}