Public Member Functions | Private Attributes | List of all members
robot_controllers::GravityCompensation Class Reference

Controller which uses KDL to compute torque needed for static holding of the chain at the current pose. More...

#include <gravity_compensation.h>

Inheritance diagram for robot_controllers::GravityCompensation:
Inheritance graph
[legend]

Public Member Functions

virtual std::vector< std::string > getClaimedNames ()
 Get the names of joints/controllers which this controller exclusively claims. More...
 
virtual std::vector< std::string > getCommandedNames ()
 Get the names of joints/controllers which this controller commands. More...
 
virtual std::string getType ()
 Get the type of this controller. More...
 
 GravityCompensation ()
 
virtual int init (ros::NodeHandle &nh, ControllerManager *manager)
 Initialize the controller and any required data structures. More...
 
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. More...
 
virtual bool start ()
 Attempt to start the controller. This should be called only by the ControllerManager instance. More...
 
virtual bool stop (bool force)
 Stop this controller. More...
 
virtual void update (const ros::Time &time, const ros::Duration &dt)
 This is the update loop for the controller. More...
 
virtual ~GravityCompensation ()
 
- Public Member Functions inherited from robot_controllers::Controller
 Controller ()
 
std::string getName ()
 
virtual ~Controller ()
 
- Public Member Functions inherited from robot_controllers::Handle
 Handle ()
 
virtual ~Handle ()
 

Private Attributes

bool initialized_
 
std::vector< JointHandlePtrjoints_
 
KDL::Chain kdl_chain_
 is KDL structure setup More...
 
boost::shared_ptr< KDL::ChainDynParamkdl_chain_dynamics_
 
ControllerManagermanager_
 
KDL::JntArrayVel positions_
 

Detailed Description

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.

Constructor & Destructor Documentation

robot_controllers::GravityCompensation::GravityCompensation ( )
inline

Definition at line 70 of file gravity_compensation.h.

virtual robot_controllers::GravityCompensation::~GravityCompensation ( )
inlinevirtual

Definition at line 71 of file gravity_compensation.h.

Member Function Documentation

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 ( )
inlinevirtual

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.

Parameters
nhNode handle for this controller.
managerThe controller manager instance, this is needed for the controller to get information about joints, etc.
Returns
0 if succesfully configured, negative values are error codes.

Reimplemented from robot_controllers::Controller.

Definition at line 46 of file gravity_compensation.cpp.

virtual bool robot_controllers::GravityCompensation::reset ( )
inlinevirtual

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.

Returns
True if successfully reset, false otherwise.

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.

Returns
True if successfully started, false otherwise.

Implements robot_controllers::Controller.

Definition at line 101 of file gravity_compensation.cpp.

virtual bool robot_controllers::GravityCompensation::stop ( bool  force)
inlinevirtual

Stop this controller.

Parameters
forceIf true, this controller will be stopped regardless of return value.
Returns
true if controller preempted successfully.

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.

Parameters
timeThe system time.
dtThe timestep since last call to update.

Implements robot_controllers::Controller.

Definition at line 108 of file gravity_compensation.cpp.

Member Data Documentation

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.

KDL::Chain robot_controllers::GravityCompensation::kdl_chain_
private

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.

ControllerManager* robot_controllers::GravityCompensation::manager_
private

Definition at line 133 of file gravity_compensation.h.

KDL::JntArrayVel robot_controllers::GravityCompensation::positions_
private

Definition at line 139 of file gravity_compensation.h.


The documentation for this class was generated from the following files:


robot_controllers
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:39