#include <pr2_joint_trajectory_client.h>
Public Member Functions | |
| actionlib::SimpleClientGoalState | getState () | 
| Returns the current state of the action.   | |
| pr2_controllers_msgs::JointTrajectoryGoal | makeArmUpTrajectory () | 
| Pr2JointTrajectoryClient () | |
| void | startTrajectory (pr2_controllers_msgs::JointTrajectoryGoal goal) | 
| Sends the command to start a given trajectory.   | |
| virtual | ~Pr2JointTrajectoryClient () | 
Private Member Functions | |
| trajectory_msgs::JointTrajectory | filterJointTrajectory (const trajectory_msgs::JointTrajectory &input) | 
| 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_ | 
| TrajClient | traj_client_ | 
Definition at line 23 of file pr2_joint_trajectory_client.h.
Definition at line 13 of file pr2_joint_trajectory_client.cpp.
Definition at line 32 of file pr2_joint_trajectory_client.cpp.
| trajectory_msgs::JointTrajectory katana_tutorials::Pr2JointTrajectoryClient::filterJointTrajectory | ( | const trajectory_msgs::JointTrajectory & | input | ) |  [private] | 
        
Definition at line 149 of file pr2_joint_trajectory_client.cpp.
Returns the current state of the action.
Definition at line 144 of file pr2_joint_trajectory_client.cpp.
| void katana_tutorials::Pr2JointTrajectoryClient::jointStateCB | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) |  [private] | 
        
Definition at line 36 of file pr2_joint_trajectory_client.cpp.
| pr2_controllers_msgs::JointTrajectoryGoal katana_tutorials::Pr2JointTrajectoryClient::makeArmUpTrajectory | ( | ) | 
Definition at line 71 of file pr2_joint_trajectory_client.cpp.
| void katana_tutorials::Pr2JointTrajectoryClient::startTrajectory | ( | pr2_controllers_msgs::JointTrajectoryGoal | goal | ) | 
Sends the command to start a given trajectory.
Definition at line 64 of file pr2_joint_trajectory_client.cpp.
std::vector<double> katana_tutorials::Pr2JointTrajectoryClient::current_joint_state_ [private] | 
        
Definition at line 39 of file pr2_joint_trajectory_client.h.
Definition at line 38 of file pr2_joint_trajectory_client.h.
std::vector<std::string> katana_tutorials::Pr2JointTrajectoryClient::joint_names_ [private] | 
        
Definition at line 37 of file pr2_joint_trajectory_client.h.
Definition at line 36 of file pr2_joint_trajectory_client.h.
Definition at line 34 of file pr2_joint_trajectory_client.h.
Definition at line 40 of file pr2_joint_trajectory_client.h.
Definition at line 35 of file pr2_joint_trajectory_client.h.