#include <pr2_gripper_controller.h>
Public Member Functions | |
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
Pr2GripperController () | |
virtual void | starting () |
virtual void | update () |
Issues commands to the joint. Should be called at regular intervals. | |
~Pr2GripperController () | |
Public Attributes | |
realtime_tools::RealtimeBox < pr2_controllers_msgs::Pr2GripperCommandConstPtr > | command_box_ |
pr2_mechanism_model::JointState * | joint_state_ |
Private Member Functions | |
void | commandCB (const pr2_controllers_msgs::Pr2GripperCommandConstPtr &msg) |
Private Attributes | |
boost::scoped_ptr < realtime_tools::RealtimePublisher < pr2_controllers_msgs::JointControllerState > > | controller_state_publisher_ |
ros::Time | last_time_ |
int | loop_count_ |
ros::NodeHandle | node_ |
control_toolbox::Pid | pid_ |
pr2_mechanism_model::RobotState * | robot_ |
ros::Subscriber | sub_command_ |
Definition at line 76 of file pr2_gripper_controller.h.
controller::Pr2GripperController::Pr2GripperController | ( | ) |
Definition at line 45 of file pr2_gripper_controller.cpp.
controller::Pr2GripperController::~Pr2GripperController | ( | ) |
Definition at line 51 of file pr2_gripper_controller.cpp.
void controller::Pr2GripperController::commandCB | ( | const pr2_controllers_msgs::Pr2GripperCommandConstPtr & | msg | ) | [private] |
Definition at line 152 of file pr2_gripper_controller.cpp.
bool controller::Pr2GripperController::init | ( | pr2_mechanism_model::RobotState * | robot, | |
ros::NodeHandle & | n | |||
) |
Definition at line 56 of file pr2_gripper_controller.cpp.
virtual void controller::Pr2GripperController::starting | ( | ) | [inline, virtual] |
Definition at line 82 of file pr2_gripper_controller.h.
void controller::Pr2GripperController::update | ( | ) | [virtual] |
Issues commands to the joint. Should be called at regular intervals.
Definition at line 100 of file pr2_gripper_controller.cpp.
realtime_tools::RealtimeBox<pr2_controllers_msgs::Pr2GripperCommandConstPtr> controller::Pr2GripperController::command_box_ |
Definition at line 96 of file pr2_gripper_controller.h.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState> > controller::Pr2GripperController::controller_state_publisher_ [private] |
Definition at line 108 of file pr2_gripper_controller.h.
pr2_mechanism_model::JointState* controller::Pr2GripperController::joint_state_ |
Definition at line 95 of file pr2_gripper_controller.h.
ros::Time controller::Pr2GripperController::last_time_ [private] |
Definition at line 102 of file pr2_gripper_controller.h.
int controller::Pr2GripperController::loop_count_ [private] |
Definition at line 99 of file pr2_gripper_controller.h.
ros::NodeHandle controller::Pr2GripperController::node_ [private] |
Definition at line 104 of file pr2_gripper_controller.h.
control_toolbox::Pid controller::Pr2GripperController::pid_ [private] |
Definition at line 101 of file pr2_gripper_controller.h.
pr2_mechanism_model::RobotState* controller::Pr2GripperController::robot_ [private] |
Definition at line 100 of file pr2_gripper_controller.h.
ros::Subscriber controller::Pr2GripperController::sub_command_ [private] |
Definition at line 110 of file pr2_gripper_controller.h.