Controller which uses KDL to compute torque needed for static holding of the chain at the current pose. More...
#include <gravity_compensation.h>

| Public Member Functions | |
| virtual std::vector< std::string > | getClaimedNames () | 
| Get the names of joints/controllers which this controller exclusively claims. | |
| virtual std::vector< std::string > | getCommandedNames () | 
| Get the names of joints/controllers which this controller commands. | |
| virtual std::string | getType () | 
| Get the type of this controller. | |
| GravityCompensation () | |
| virtual int | init (ros::NodeHandle &nh, ControllerManager *manager) | 
| Initialize the controller and any required data structures. | |
| virtual bool | reset () | 
| Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition. | |
| virtual bool | start () | 
| Attempt to start the controller. This should be called only by the ControllerManager instance. | |
| virtual bool | stop (bool force) | 
| Stop this controller. | |
| virtual void | update (const ros::Time &time, const ros::Duration &dt) | 
| This is the update loop for the controller. | |
| virtual | ~GravityCompensation () | 
| Private Attributes | |
| bool | initialized_ | 
| std::vector< JointHandlePtr > | joints_ | 
| KDL::Chain | kdl_chain_ | 
| is KDL structure setup | |
| boost::shared_ptr < KDL::ChainDynParam > | kdl_chain_dynamics_ | 
| ControllerManager * | manager_ | 
| KDL::JntArrayVel | positions_ | 
Controller which uses KDL to compute torque needed for static holding of the chain at the current pose.
Definition at line 67 of file gravity_compensation.h.
Definition at line 70 of file gravity_compensation.h.
| virtual robot_controllers::GravityCompensation::~GravityCompensation | ( | ) |  [inline, virtual] | 
Definition at line 71 of file gravity_compensation.h.
| std::vector< std::string > robot_controllers::GravityCompensation::getClaimedNames | ( | ) |  [virtual] | 
Get the names of joints/controllers which this controller exclusively claims.
Implements robot_controllers::Controller.
Definition at line 139 of file gravity_compensation.cpp.
| std::vector< std::string > robot_controllers::GravityCompensation::getCommandedNames | ( | ) |  [virtual] | 
Get the names of joints/controllers which this controller commands.
Implements robot_controllers::Controller.
Definition at line 127 of file gravity_compensation.cpp.
| virtual std::string robot_controllers::GravityCompensation::getType | ( | ) |  [inline, virtual] | 
Get the type of this controller.
Reimplemented from robot_controllers::Controller.
Definition at line 121 of file gravity_compensation.h.
| int robot_controllers::GravityCompensation::init | ( | ros::NodeHandle & | nh, | 
| ControllerManager * | manager | ||
| ) |  [virtual] | 
Initialize the controller and any required data structures.
| nh | Node handle for this controller. | 
| manager | The controller manager instance, this is needed for the controller to get information about joints, etc. | 
Reimplemented from robot_controllers::Controller.
Definition at line 46 of file gravity_compensation.cpp.
| virtual bool robot_controllers::GravityCompensation::reset | ( | ) |  [inline, virtual] | 
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition.
Implements robot_controllers::Controller.
Definition at line 107 of file gravity_compensation.h.
| bool robot_controllers::GravityCompensation::start | ( | ) |  [virtual] | 
Attempt to start the controller. This should be called only by the ControllerManager instance.
Implements robot_controllers::Controller.
Definition at line 101 of file gravity_compensation.cpp.
| virtual bool robot_controllers::GravityCompensation::stop | ( | bool | force | ) |  [inline, virtual] | 
Stop this controller.
| force | If true, this controller will be stopped regardless of return value. | 
Implements robot_controllers::Controller.
Definition at line 95 of file gravity_compensation.h.
| void robot_controllers::GravityCompensation::update | ( | const ros::Time & | time, | 
| const ros::Duration & | dt | ||
| ) |  [virtual] | 
This is the update loop for the controller.
| time | The system time. | 
| dt | The timestep since last call to update. | 
Implements robot_controllers::Controller.
Definition at line 108 of file gravity_compensation.cpp.
| bool robot_controllers::GravityCompensation::initialized_  [private] | 
Definition at line 136 of file gravity_compensation.h.
| std::vector<JointHandlePtr> robot_controllers::GravityCompensation::joints_  [private] | 
Definition at line 134 of file gravity_compensation.h.
is KDL structure setup
Definition at line 138 of file gravity_compensation.h.
| boost::shared_ptr<KDL::ChainDynParam> robot_controllers::GravityCompensation::kdl_chain_dynamics_  [private] | 
Definition at line 140 of file gravity_compensation.h.
Definition at line 133 of file gravity_compensation.h.
Definition at line 139 of file gravity_compensation.h.