48 Controller::init(nh, manager);
53 if (!model.
initParam(
"robot_description"))
63 ROS_ERROR(
"Could not construct tree from URDF");
68 std::string root, tip;
69 nh.
param<std::string>(
"root", root,
"torso_lift_link");
70 nh.
param<std::string>(
"tip", tip,
"wrist_roll_link");
71 if(!kdl_tree.
getChain(root, tip, kdl_chain_))
73 ROS_ERROR(
"Could not construct chain from URDF");
86 for (
size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
88 joints_.push_back(manager_->getJointHandle(kdl_chain_.getSegment(i).getJoint().getName()));
94 nh.
param(
"autostart", autostart,
false);
101 bool GravityCompensation::start()
115 for (
size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
116 positions_.q.data[i] = joints_[i]->getPosition();
120 kdl_chain_dynamics_->JntToGravity(positions_.q, torques);
123 for (
size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
124 joints_[i]->setEffort(torques.data[i]);
127 std::vector<std::string> GravityCompensation::getCommandedNames()
129 std::vector<std::string> names;
132 for (
size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
134 names.push_back(kdl_chain_.getSegment(i).getJoint().getName());
139 std::vector<std::string> GravityCompensation::getClaimedNames()
142 std::vector<std::string> names;
Controller which uses KDL to compute torque needed for static holding of the chain at the current pos...
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
std::string getName(void *handle)
virtual int requestStart(const std::string &name)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
URDF_EXPORT bool initParam(const std::string ¶m)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
void SetToZero(Jacobian &jac)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)