Controller for a parallel jaw gripper, is really only intended for use in simulation. More...
#include <parallel_gripper.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. | |
virtual int | init (ros::NodeHandle &nh, ControllerManager *manager) |
Initialize the controller and any required data structures. | |
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. | |
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 | ~ParallelGripperController () |
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_ |
ControllerManager * | manager_ |
double | max_effort_ |
double | max_position_ |
JointHandlePtr | right_ |
boost::shared_ptr< server_t > | server_ |
bool | use_centering_controller_ |
Controller for a parallel jaw gripper, is really only intended for use in simulation.
Definition at line 58 of file parallel_gripper.h.
typedef actionlib::SimpleActionServer<control_msgs::GripperCommandAction> robot_controllers::ParallelGripperController::server_t [private] |
Definition at line 60 of file parallel_gripper.h.
Definition at line 63 of file parallel_gripper.h.
virtual robot_controllers::ParallelGripperController::~ParallelGripperController | ( | ) | [inline, virtual] |
Definition at line 66 of file parallel_gripper.h.
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 | ( | ) | [inline, virtual] |
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.
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 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.
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.
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.
force | Should we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop. |
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.
time | The system time. |
dt | The timestep since last call to update. |
Implements robot_controllers::Controller.
Definition at line 154 of file parallel_gripper.cpp.
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.
Definition at line 126 of file parallel_gripper.h.
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.
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.
Definition at line 132 of file parallel_gripper.h.