The CModelGripperActionServer class. Takes as arguments the name of the gripper it is to command, and a set of parameters that define the physical characteristics of the particular gripper. More...
#include <robotiq_c_model_action_server.h>
| Public Member Functions | |
| void | analysisCB (const GripperInput::ConstPtr &msg) | 
| CModelGripperActionServer (const std::string &name, const CModelGripperParams ¶ms) | |
| void | goalCB () | 
| void | preemptCB () | 
| Private Member Functions | |
| void | issueActivation () | 
| Private Attributes | |
| std::string | action_name_ | 
| actionlib::SimpleActionServer < control_msgs::GripperCommandAction > | as_ | 
| GripperInput | current_reg_state_ | 
| ros::Publisher | goal_pub_ | 
| GripperOutput | goal_reg_state_ | 
| CModelGripperParams | gripper_params_ | 
| ros::NodeHandle | nh_ | 
| ros::Subscriber | state_sub_ | 
The CModelGripperActionServer class. Takes as arguments the name of the gripper it is to command, and a set of parameters that define the physical characteristics of the particular gripper.
Listens for messages on input and publishes on output. Remap these.
Definition at line 52 of file robotiq_c_model_action_server.h.
| robotiq_action_server::CModelGripperActionServer::CModelGripperActionServer | ( | const std::string & | name, | 
| const CModelGripperParams & | params | ||
| ) | 
Definition at line 92 of file robotiq_c_model_action_server.cpp.
| void robotiq_action_server::CModelGripperActionServer::analysisCB | ( | const GripperInput::ConstPtr & | msg | ) | 
Definition at line 140 of file robotiq_c_model_action_server.cpp.
Definition at line 107 of file robotiq_c_model_action_server.cpp.
| void robotiq_action_server::CModelGripperActionServer::issueActivation | ( | ) |  [private] | 
Definition at line 187 of file robotiq_c_model_action_server.cpp.
Definition at line 134 of file robotiq_c_model_action_server.cpp.
| std::string robotiq_action_server::CModelGripperActionServer::action_name_  [private] | 
Definition at line 79 of file robotiq_c_model_action_server.h.
| actionlib::SimpleActionServer<control_msgs::GripperCommandAction> robotiq_action_server::CModelGripperActionServer::as_  [private] | 
Definition at line 66 of file robotiq_c_model_action_server.h.
Definition at line 72 of file robotiq_c_model_action_server.h.
Definition at line 69 of file robotiq_c_model_action_server.h.
Definition at line 71 of file robotiq_c_model_action_server.h.
Definition at line 77 of file robotiq_c_model_action_server.h.
Definition at line 65 of file robotiq_c_model_action_server.h.
Definition at line 68 of file robotiq_c_model_action_server.h.