Controller for a parallel jaw gripper, is really only intended for use in simulation.
More...
#include <parallel_gripper.h>
|
void | executeCb (const control_msgs::GripperCommandGoalConstPtr &goal) |
|
Controller for a parallel jaw gripper, is really only intended for use in simulation.
Definition at line 58 of file parallel_gripper.h.
robot_controllers::ParallelGripperController::ParallelGripperController |
( |
| ) |
|
|
inline |
virtual robot_controllers::ParallelGripperController::~ParallelGripperController |
( |
| ) |
|
|
inlinevirtual |
void robot_controllers::ParallelGripperController::executeCb |
( |
const control_msgs::GripperCommandGoalConstPtr & |
goal | ) |
|
|
private |
std::vector< std::string > robot_controllers::ParallelGripperController::getClaimedNames |
( |
| ) |
|
|
virtual |
std::vector< std::string > robot_controllers::ParallelGripperController::getCommandedNames |
( |
| ) |
|
|
virtual |
virtual std::string robot_controllers::ParallelGripperController::getType |
( |
| ) |
|
|
inlinevirtual |
Initialize the controller and any required data structures.
- Parameters
-
nh | Node handle for this controller. |
manager | The 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 |
bool robot_controllers::ParallelGripperController::stop |
( |
bool |
force | ) |
|
|
virtual |
Attempt to stop the controller. This should be called only by the ControllerManager instance.
- Parameters
-
force | Should 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.
double robot_controllers::ParallelGripperController::effort_ |
|
private |
double robot_controllers::ParallelGripperController::goal_ |
|
private |
bool robot_controllers::ParallelGripperController::initialized_ |
|
private |
double robot_controllers::ParallelGripperController::max_effort_ |
|
private |
double robot_controllers::ParallelGripperController::max_position_ |
|
private |
bool robot_controllers::ParallelGripperController::use_centering_controller_ |
|
private |
The documentation for this class was generated from the following files: