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");
73 ROS_ERROR(
"Could not construct chain from URDF");
94 nh.
param(
"autostart", autostart,
false);
124 joints_[i]->setEffort(torques.data[i]);
129 std::vector<std::string> names;
142 std::vector<std::string> names;
Controller which uses KDL to compute torque needed for static holding of the chain at the current pos...
virtual void update(const ros::Time &time, const ros::Duration &dt)
This is the update loop for the controller.
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
ControllerManager * manager_
unsigned int getNrOfSegments() const
const Segment & getSegment(unsigned int nr) const
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
virtual int requestStart(const std::string &name)
const Joint & getJoint() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
unsigned int getNrOfJoints() const
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
KDL::Chain kdl_chain_
is KDL structure setup
boost::shared_ptr< KDL::ChainDynParam > kdl_chain_dynamics_
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
URDF_EXPORT bool initParam(const std::string ¶m)
const JointType & getType() const
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
void SetToZero(Jacobian &jac)
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
std::vector< JointHandlePtr > joints_
const std::string & getName() const
JointHandlePtr getJointHandle(const std::string &name)
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
KDL::JntArrayVel positions_