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

Controller for a parallel jaw gripper, is really only intended for use in simulation. More...

#include <parallel_gripper.h>

Inheritance diagram for robot_controllers::ParallelGripperController:
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...
 
virtual int init (ros::NodeHandle &nh, ControllerManager *manager)
 Initialize the controller and any required data structures. More...
 
 ParallelGripperController ()
 
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)
 Attempt to stop the controller. This should be called only by the ControllerManager instance. More...
 
virtual void update (const ros::Time &now, const ros::Duration &dt)
 This is the update loop for the controller. More...
 
virtual ~ParallelGripperController ()
 
- 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 Types

typedef actionlib::SimpleActionServer< control_msgs::GripperCommandAction > server_t
 

Private Member Functions

void executeCb (const control_msgs::GripperCommandGoalConstPtr &goal)
 

Private Attributes

robot_controllers::PID centering_pid_
 
double effort_
 
double goal_
 
bool initialized_
 
JointHandlePtr left_
 
ControllerManagermanager_
 
double max_effort_
 
double max_position_
 
JointHandlePtr right_
 
boost::shared_ptr< server_tserver_
 
bool use_centering_controller_
 

Detailed Description

Controller for a parallel jaw gripper, is really only intended for use in simulation.

Definition at line 58 of file parallel_gripper.h.

Member Typedef Documentation

Definition at line 60 of file parallel_gripper.h.

Constructor & Destructor Documentation

robot_controllers::ParallelGripperController::ParallelGripperController ( )
inline

Definition at line 63 of file parallel_gripper.h.

virtual robot_controllers::ParallelGripperController::~ParallelGripperController ( )
inlinevirtual

Definition at line 66 of file parallel_gripper.h.

Member Function Documentation

void robot_controllers::ParallelGripperController::executeCb ( const control_msgs::GripperCommandGoalConstPtr &  goal)
private

Definition at line 180 of file parallel_gripper.cpp.

std::vector< std::string > robot_controllers::ParallelGripperController::getClaimedNames ( )
virtual

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

Implements robot_controllers::Controller.

Definition at line 289 of file parallel_gripper.cpp.

std::vector< std::string > robot_controllers::ParallelGripperController::getCommandedNames ( )
virtual

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

Implements robot_controllers::Controller.

Definition at line 281 of file parallel_gripper.cpp.

virtual std::string robot_controllers::ParallelGripperController::getType ( )
inlinevirtual

Get the type of this controller.

Reimplemented from robot_controllers::Controller.

Definition at line 109 of file parallel_gripper.h.

int robot_controllers::ParallelGripperController::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 parallel_gripper.cpp.

bool robot_controllers::ParallelGripperController::reset ( )
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.

Returns
True if successfully reset, false otherwise.

Implements robot_controllers::Controller.

Definition at line 148 of file parallel_gripper.cpp.

bool robot_controllers::ParallelGripperController::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 107 of file parallel_gripper.cpp.

bool robot_controllers::ParallelGripperController::stop ( bool  force)
virtual

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 126 of file parallel_gripper.cpp.

void robot_controllers::ParallelGripperController::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 154 of file parallel_gripper.cpp.

Member Data Documentation

robot_controllers::PID robot_controllers::ParallelGripperController::centering_pid_
private

Definition at line 133 of file parallel_gripper.h.

double robot_controllers::ParallelGripperController::effort_
private

Definition at line 129 of file parallel_gripper.h.

double robot_controllers::ParallelGripperController::goal_
private

Definition at line 129 of file parallel_gripper.h.

bool robot_controllers::ParallelGripperController::initialized_
private

Definition at line 123 of file parallel_gripper.h.

JointHandlePtr robot_controllers::ParallelGripperController::left_
private

Definition at line 126 of file parallel_gripper.h.

ControllerManager* robot_controllers::ParallelGripperController::manager_
private

Definition at line 124 of file parallel_gripper.h.

double robot_controllers::ParallelGripperController::max_effort_
private

Definition at line 129 of file parallel_gripper.h.

double robot_controllers::ParallelGripperController::max_position_
private

Definition at line 129 of file parallel_gripper.h.

JointHandlePtr robot_controllers::ParallelGripperController::right_
private

Definition at line 127 of file parallel_gripper.h.

boost::shared_ptr<server_t> robot_controllers::ParallelGripperController::server_
private

Definition at line 130 of file parallel_gripper.h.

bool robot_controllers::ParallelGripperController::use_centering_controller_
private

Definition at line 132 of file parallel_gripper.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