#include <katana_gripper_grasp_controller.h>
|
void | executeCB (const control_msgs::GripperCommandGoalConstPtr &goal) |
|
bool | serviceCallback (control_msgs::QueryTrajectoryState::Request &request, control_msgs::QueryTrajectoryState::Response &response) |
|
void | setDesiredAngle (double desired_angle) |
|
katana_gazebo_plugins::KatanaGripperGraspController::KatanaGripperGraspController |
( |
ros::NodeHandle |
private_nodehandle | ) |
|
katana_gazebo_plugins::KatanaGripperGraspController::~KatanaGripperGraspController |
( |
| ) |
|
|
virtual |
void katana_gazebo_plugins::KatanaGripperGraspController::cancelGoal |
( |
| ) |
|
|
inlinevirtual |
void katana_gazebo_plugins::KatanaGripperGraspController::executeCB |
( |
const control_msgs::GripperCommandGoalConstPtr & |
goal | ) |
|
|
private |
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 |
void katana_gazebo_plugins::KatanaGripperGraspController::setCurrentPoint |
( |
GRKAPoint |
point | ) |
|
|
inlinevirtual |
void katana_gazebo_plugins::KatanaGripperGraspController::setDesiredAngle |
( |
double |
desired_angle | ) |
|
|
inlineprivate |
double katana_gazebo_plugins::KatanaGripperGraspController::current_angle_ |
|
private |
double katana_gazebo_plugins::KatanaGripperGraspController::desired_angle_ |
|
private |
double katana_gazebo_plugins::KatanaGripperGraspController::goal_threshold_ |
|
private |
double katana_gazebo_plugins::KatanaGripperGraspController::gripper_object_presence_threshold_ |
|
private |
bool katana_gazebo_plugins::KatanaGripperGraspController::has_new_desired_angle_ |
|
private |
The documentation for this class was generated from the following files: