Public Member Functions | Private Member Functions | Private Attributes
katana_gazebo_plugins::KatanaGripperGraspController Class Reference

#include <katana_gripper_grasp_controller.h>

Inheritance diagram for katana_gazebo_plugins::KatanaGripperGraspController:
Inheritance graph
[legend]

List of all members.

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 control_msgs::GripperCommandGoalConstPtr &goal)
bool serviceCallback (control_msgs::QueryTrajectoryState::Request &request, control_msgs::QueryTrajectoryState::Response &response)
void setDesiredAngle (double desired_angle)

Private Attributes

actionlib::SimpleActionServer
< control_msgs::GripperCommandAction > * 
action_server_
 Action server for the grasp posture action.
double current_angle_
double desired_angle_
double goal_threshold_
double gripper_object_presence_threshold_
 A joint angle below this value indicates there is nothing inside the gripper.
bool has_new_desired_angle_
ros::ServiceServer query_srv_
 Server for the posture query service.

Detailed Description

Definition at line 42 of file katana_gripper_grasp_controller.h.


Constructor & Destructor Documentation

Definition at line 44 of file katana_gripper_grasp_controller.cpp.

Definition at line 62 of file katana_gripper_grasp_controller.cpp.


Member Function Documentation

void katana_gazebo_plugins::KatanaGripperGraspController::executeCB ( const control_msgs::GripperCommandGoalConstPtr &  goal) [private]

Definition at line 67 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]
bool katana_gazebo_plugins::KatanaGripperGraspController::serviceCallback ( control_msgs::QueryTrajectoryState::Request &  request,
control_msgs::QueryTrajectoryState::Response &  response 
) [private]

Definition at line 100 of file katana_gripper_grasp_controller.cpp.

void katana_gazebo_plugins::KatanaGripperGraspController::setDesiredAngle ( double  desired_angle) [inline, private]

Definition at line 90 of file katana_gripper_grasp_controller.h.


Member Data Documentation

Action server for the grasp posture action.

Definition at line 77 of file katana_gripper_grasp_controller.h.

Definition at line 98 of file katana_gripper_grasp_controller.h.

Definition at line 97 of file katana_gripper_grasp_controller.h.

Definition at line 96 of file katana_gripper_grasp_controller.h.

A joint angle below this value indicates there is nothing inside the gripper.

Definition at line 83 of file katana_gripper_grasp_controller.h.

Definition at line 99 of file katana_gripper_grasp_controller.h.

Server for the posture query service.

Definition at line 80 of file katana_gripper_grasp_controller.h.


The documentation for this class was generated from the following files:


katana_gazebo_plugins
Author(s): Martin Günther
autogenerated on Thu Aug 27 2015 13:39:55