$search
#include <katana_gripper_grasp_controller.h>
Public Member Functions | |
void | cancelGoal () |
void | getGains (double &p, double &i, double &d, double &i_max, double &i_min) |
GRKAPoint | getNextDesiredPoint (ros::Time time) |
bool | hasActiveGoal () const |
KatanaGripperGraspController (ros::NodeHandle private_nodehandle) | |
void | setCurrentPoint (GRKAPoint point) |
virtual | ~KatanaGripperGraspController () |
Private Member Functions | |
void | executeCB (const object_manipulation_msgs::GraspHandPostureExecutionGoalConstPtr &goal) |
bool | serviceCallback (object_manipulation_msgs::GraspStatus::Request &request, object_manipulation_msgs::GraspStatus::Response &response) |
void | setDesiredAngle (double desired_angle) |
Private Attributes | |
actionlib::SimpleActionServer < object_manipulation_msgs::GraspHandPostureExecutionAction > * | action_server_ |
Action server for the grasp posture action. | |
double | current_angle_ |
double | desired_angle_ |
double | gripper_object_presence_threshold_ |
A joint angle below this value indicates there is nothing inside the gripper. | |
bool | has_new_desired_angle_ |
bool | last_command_was_close_ |
ros::ServiceServer | query_srv_ |
Server for the posture query service. |
Definition at line 42 of file katana_gripper_grasp_controller.h.
katana_gazebo_plugins::KatanaGripperGraspController::KatanaGripperGraspController | ( | ros::NodeHandle | private_nodehandle | ) |
Definition at line 47 of file katana_gripper_grasp_controller.cpp.
katana_gazebo_plugins::KatanaGripperGraspController::~KatanaGripperGraspController | ( | ) | [virtual] |
Definition at line 73 of file katana_gripper_grasp_controller.cpp.
void katana_gazebo_plugins::KatanaGripperGraspController::cancelGoal | ( | ) | [inline, virtual] |
Implements katana_gazebo_plugins::IGazeboRosKatanaGripperAction.
Definition at line 70 of file katana_gripper_grasp_controller.h.
void katana_gazebo_plugins::KatanaGripperGraspController::executeCB | ( | const object_manipulation_msgs::GraspHandPostureExecutionGoalConstPtr & | goal | ) | [private] |
Definition at line 78 of file katana_gripper_grasp_controller.cpp.
void katana_gazebo_plugins::KatanaGripperGraspController::getGains | ( | double & | p, | |
double & | i, | |||
double & | d, | |||
double & | i_max, | |||
double & | i_min | |||
) | [virtual] |
Implements katana_gazebo_plugins::IGazeboRosKatanaGripperAction.
Definition at line 179 of file katana_gripper_grasp_controller.cpp.
GRKAPoint katana_gazebo_plugins::KatanaGripperGraspController::getNextDesiredPoint | ( | ros::Time | time | ) | [inline, virtual] |
Implements katana_gazebo_plugins::IGazeboRosKatanaGripperAction.
Definition at line 48 of file katana_gripper_grasp_controller.h.
bool katana_gazebo_plugins::KatanaGripperGraspController::hasActiveGoal | ( | ) | const [inline, virtual] |
Implements katana_gazebo_plugins::IGazeboRosKatanaGripperAction.
Definition at line 63 of file katana_gripper_grasp_controller.h.
bool katana_gazebo_plugins::KatanaGripperGraspController::serviceCallback | ( | object_manipulation_msgs::GraspStatus::Request & | request, | |
object_manipulation_msgs::GraspStatus::Response & | response | |||
) | [private] |
Definition at line 154 of file katana_gripper_grasp_controller.cpp.
void katana_gazebo_plugins::KatanaGripperGraspController::setCurrentPoint | ( | GRKAPoint | point | ) | [inline, virtual] |
Implements katana_gazebo_plugins::IGazeboRosKatanaGripperAction.
Definition at line 58 of file katana_gripper_grasp_controller.h.
void katana_gazebo_plugins::KatanaGripperGraspController::setDesiredAngle | ( | double | desired_angle | ) | [inline, private] |
Definition at line 92 of file katana_gripper_grasp_controller.h.
actionlib::SimpleActionServer<object_manipulation_msgs::GraspHandPostureExecutionAction>* katana_gazebo_plugins::KatanaGripperGraspController::action_server_ [private] |
Action server for the grasp posture action.
Definition at line 77 of file katana_gripper_grasp_controller.h.
double katana_gazebo_plugins::KatanaGripperGraspController::current_angle_ [private] |
Definition at line 99 of file katana_gripper_grasp_controller.h.
double katana_gazebo_plugins::KatanaGripperGraspController::desired_angle_ [private] |
Definition at line 98 of file katana_gripper_grasp_controller.h.
double katana_gazebo_plugins::KatanaGripperGraspController::gripper_object_presence_threshold_ [private] |
A joint angle below this value indicates there is nothing inside the gripper.
Definition at line 85 of file katana_gripper_grasp_controller.h.
Definition at line 100 of file katana_gripper_grasp_controller.h.
Definition at line 82 of file katana_gripper_grasp_controller.h.
Server for the posture query service.
Definition at line 80 of file katana_gripper_grasp_controller.h.