38 #ifndef ROBOT_CONTROLLERS_GRAVITY_COMPENSATION_H_ 39 #define ROBOT_CONTROLLERS_GRAVITY_COMPENSATION_H_ 43 #include <boost/shared_ptr.hpp> 53 #include <kdl/tree.hpp> 54 #include <kdl/chain.hpp> 55 #include <kdl/jntarray.hpp> 56 #include <kdl/jntarrayvel.hpp> 57 #include <kdl/chaindynparam.hpp> 95 virtual bool stop(
bool force)
123 return "robot_controllers/GravityCompensation";
145 #endif // ROBOT_CONTROLLERS_GRAVITY_COMPENSATION_H_
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.
virtual std::string getType()
Get the type of this controller.
virtual ~GravityCompensation()
ControllerManager * manager_
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
virtual bool stop(bool force)
Stop this controller.
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
KDL::Chain kdl_chain_
is KDL structure setup
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
boost::shared_ptr< KDL::ChainDynParam > kdl_chain_dynamics_
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
std::vector< JointHandlePtr > joints_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
KDL::JntArrayVel positions_