Public Member Functions | Private Member Functions | Private Attributes | List of all members
katana_gazebo_plugins::KatanaGripperGraspController Class Reference

#include <katana_gripper_grasp_controller.h>

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

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 ()
 
- Public Member Functions inherited from katana_gazebo_plugins::IGazeboRosKatanaGripperAction
virtual void setCurrentPoint (double pos, double vel)
 
virtual ~IGazeboRosKatanaGripperAction ()
 

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. More...
 
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. More...
 
bool has_new_desired_angle_
 
ros::ServiceServer query_srv_
 Server for the posture query service. More...
 

Detailed Description

Definition at line 42 of file katana_gripper_grasp_controller.h.

Constructor & Destructor Documentation

katana_gazebo_plugins::KatanaGripperGraspController::KatanaGripperGraspController ( ros::NodeHandle  private_nodehandle)

Definition at line 44 of file katana_gripper_grasp_controller.cpp.

katana_gazebo_plugins::KatanaGripperGraspController::~KatanaGripperGraspController ( )
virtual

Definition at line 62 of file katana_gripper_grasp_controller.cpp.

Member Function Documentation

void katana_gazebo_plugins::KatanaGripperGraspController::cancelGoal ( )
inlinevirtual
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
GRKAPoint katana_gazebo_plugins::KatanaGripperGraspController::getNextDesiredPoint ( ros::Time  time)
inlinevirtual
bool katana_gazebo_plugins::KatanaGripperGraspController::hasActiveGoal ( ) const
inlinevirtual
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::setCurrentPoint ( GRKAPoint  point)
inlinevirtual
void katana_gazebo_plugins::KatanaGripperGraspController::setDesiredAngle ( double  desired_angle)
inlineprivate

Definition at line 90 of file katana_gripper_grasp_controller.h.

Member Data Documentation

actionlib::SimpleActionServer<control_msgs::GripperCommandAction>* 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 98 of file katana_gripper_grasp_controller.h.

double katana_gazebo_plugins::KatanaGripperGraspController::desired_angle_
private

Definition at line 97 of file katana_gripper_grasp_controller.h.

double katana_gazebo_plugins::KatanaGripperGraspController::goal_threshold_
private

Definition at line 96 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 83 of file katana_gripper_grasp_controller.h.

bool katana_gazebo_plugins::KatanaGripperGraspController::has_new_desired_angle_
private

Definition at line 99 of file katana_gripper_grasp_controller.h.

ros::ServiceServer katana_gazebo_plugins::KatanaGripperGraspController::query_srv_
private

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 Fri Jan 3 2020 04:01:10