Public Member Functions | Private Member Functions | Private Attributes
robot_controllers::CartesianWrenchController Class Reference

#include <cartesian_wrench.h>

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

List of all members.

Public Member Functions

 CartesianWrenchController ()
void command (const geometry_msgs::Wrench::ConstPtr &goal)
 Controller command.
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.
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)
 Attempt to stop the controller. This should be called only by the ControllerManager instance.
virtual void update (const ros::Time &now, const ros::Duration &dt)
 This is the update loop for the controller.
virtual ~CartesianWrenchController ()

Private Member Functions

void updateJoints ()

Private Attributes

ros::Subscriber command_sub_
KDL::Wrench desired_wrench_
bool enabled_
ros::Publisher feedback_pub_
bool initialized_
boost::shared_ptr
< KDL::ChainJntToJacSolver
jac_solver_
KDL::Jacobian jacobian_
KDL::JntArray jnt_eff_
KDL::JntArray jnt_pos_
std::vector< JointHandlePtrjoints_
KDL::Chain kdl_chain_
ros::Time last_command_
ControllerManagermanager_
std::string root_link_
tf::TransformListener tf_

Detailed Description

Definition at line 65 of file cartesian_wrench.h.


Constructor & Destructor Documentation

Definition at line 53 of file cartesian_wrench.cpp.

Definition at line 69 of file cartesian_wrench.h.


Member Function Documentation

void robot_controllers::CartesianWrenchController::command ( const geometry_msgs::Wrench::ConstPtr &  goal)

Controller command.

Definition at line 186 of file cartesian_wrench.cpp.

std::vector< std::string > robot_controllers::CartesianWrenchController::getClaimedNames ( ) [virtual]

Get the names of joints/controllers which this controller exclusively claims.

Implements robot_controllers::Controller.

Definition at line 219 of file cartesian_wrench.cpp.

std::vector< std::string > robot_controllers::CartesianWrenchController::getCommandedNames ( ) [virtual]

Get the names of joints/controllers which this controller commands.

Implements robot_controllers::Controller.

Definition at line 207 of file cartesian_wrench.cpp.

virtual std::string robot_controllers::CartesianWrenchController::getType ( ) [inline, virtual]

Get the type of this controller.

Reimplemented from robot_controllers::Controller.

Definition at line 112 of file cartesian_wrench.h.

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 58 of file cartesian_wrench.cpp.

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 142 of file cartesian_wrench.cpp.

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 118 of file cartesian_wrench.cpp.

Attempt to stop the controller. This should be called only by the ControllerManager instance.

Parameters:
forceShould we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop.
Returns:
True if successfully stopped, false otherwise.

Implements robot_controllers::Controller.

Definition at line 137 of file cartesian_wrench.cpp.

void robot_controllers::CartesianWrenchController::update ( const ros::Time now,
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 148 of file cartesian_wrench.cpp.

Definition at line 180 of file cartesian_wrench.cpp.


Member Data Documentation

Definition at line 145 of file cartesian_wrench.h.

Definition at line 136 of file cartesian_wrench.h.

Definition at line 132 of file cartesian_wrench.h.

Definition at line 144 of file cartesian_wrench.h.

Definition at line 129 of file cartesian_wrench.h.

Definition at line 139 of file cartesian_wrench.h.

Definition at line 142 of file cartesian_wrench.h.

Definition at line 141 of file cartesian_wrench.h.

Definition at line 140 of file cartesian_wrench.h.

Definition at line 148 of file cartesian_wrench.h.

Definition at line 138 of file cartesian_wrench.h.

Definition at line 134 of file cartesian_wrench.h.

Definition at line 130 of file cartesian_wrench.h.

Definition at line 133 of file cartesian_wrench.h.

Definition at line 147 of file cartesian_wrench.h.


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


robot_controllers
Author(s): Michael Ferguson
autogenerated on Wed Jun 14 2017 04:09:10