Public Member Functions | Private Member Functions | Private Attributes
TestGripperJointTrajectory Class Reference

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

List of all members.

Public Member Functions

control_msgs::JointTrajectoryGoal closeGoal ()
actionlib::SimpleClientGoalState getState ()
 Returns the current state of the action.
control_msgs::JointTrajectoryGoal openGoal ()
void startTrajectory (control_msgs::JointTrajectoryGoal goal)
 Sends the command to start a given trajectory.
 TestGripperJointTrajectory ()
 ~TestGripperJointTrajectory ()

Private Member Functions

void jointStateCB (const sensor_msgs::JointState::ConstPtr &msg)

Private Attributes

std::vector< double > current_joint_state_
bool got_joint_state_
std::vector< std::string > joint_names_
ros::Subscriber joint_state_sub_
ros::NodeHandle nh_
ros::AsyncSpinner spinner_
TrajClienttraj_client_

Detailed Description

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

The maximum time it takes to open or close the gripper

Definition at line 46 of file test_gripper_joint_trajectory.cpp.


Constructor & Destructor Documentation

Definition at line 90 of file test_gripper_joint_trajectory.cpp.

Definition at line 112 of file test_gripper_joint_trajectory.cpp.


Member Function Documentation

control_msgs::JointTrajectoryGoal TestGripperJointTrajectory::closeGoal ( ) [inline]

Definition at line 125 of file test_gripper_joint_trajectory.cpp.

Returns the current state of the action.

Definition at line 209 of file test_gripper_joint_trajectory.cpp.

void TestGripperJointTrajectory::jointStateCB ( const sensor_msgs::JointState::ConstPtr &  msg) [inline, private]

Definition at line 62 of file test_gripper_joint_trajectory.cpp.

control_msgs::JointTrajectoryGoal TestGripperJointTrajectory::openGoal ( ) [inline]

Definition at line 167 of file test_gripper_joint_trajectory.cpp.

void TestGripperJointTrajectory::startTrajectory ( control_msgs::JointTrajectoryGoal  goal) [inline]

Sends the command to start a given trajectory.

Definition at line 118 of file test_gripper_joint_trajectory.cpp.


Member Data Documentation

std::vector<double> TestGripperJointTrajectory::current_joint_state_ [private]

Definition at line 58 of file test_gripper_joint_trajectory.cpp.

Definition at line 57 of file test_gripper_joint_trajectory.cpp.

std::vector<std::string> TestGripperJointTrajectory::joint_names_ [private]

Definition at line 56 of file test_gripper_joint_trajectory.cpp.

Definition at line 55 of file test_gripper_joint_trajectory.cpp.

Definition at line 53 of file test_gripper_joint_trajectory.cpp.

Definition at line 59 of file test_gripper_joint_trajectory.cpp.

Definition at line 51 of file test_gripper_joint_trajectory.cpp.


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


katana_gazebo_plugins
Author(s): Martin Günther
autogenerated on Mon Aug 14 2017 02:44:02