Public Member Functions | |
double | getJointPos (const std::string &joint_name) |
int | playMotion (const std::string &motion_name, bool skip_planning) |
PlayMotionTestClient () | |
void | shouldFailWithCode (int code) |
void | shouldFinishWith (int code, int gstate) |
void | shouldSucceed () |
Protected Member Functions | |
void | jsCb (const sensor_msgs::JointStatePtr &js) |
Private Types | |
typedef actionlib::SimpleActionClient < play_motion_msgs::PlayMotionAction > | ActionClient |
typedef boost::shared_ptr < ActionClient > | ActionClientPtr |
typedef play_motion_msgs::PlayMotionGoal | ActionGoal |
typedef actionlib::SimpleClientGoalState | ActionGoalState |
typedef boost::shared_ptr < ActionGoalState > | ActionGoalStatePtr |
Private Attributes | |
ActionClientPtr | ac_ |
ActionGoalStatePtr | gs_ |
sensor_msgs::JointState | js_ |
ros::Subscriber | js_sub_ |
ros::NodeHandle | nh_ |
int | ret_ |
Definition at line 43 of file play_motion_test.cpp.
typedef actionlib::SimpleActionClient<play_motion_msgs::PlayMotionAction> PlayMotionTestClient::ActionClient [private] |
Definition at line 45 of file play_motion_test.cpp.
typedef boost::shared_ptr<ActionClient> PlayMotionTestClient::ActionClientPtr [private] |
Definition at line 46 of file play_motion_test.cpp.
typedef play_motion_msgs::PlayMotionGoal PlayMotionTestClient::ActionGoal [private] |
Definition at line 47 of file play_motion_test.cpp.
typedef actionlib::SimpleClientGoalState PlayMotionTestClient::ActionGoalState [private] |
Definition at line 48 of file play_motion_test.cpp.
typedef boost::shared_ptr<ActionGoalState> PlayMotionTestClient::ActionGoalStatePtr [private] |
Definition at line 49 of file play_motion_test.cpp.
PlayMotionTestClient::PlayMotionTestClient | ( | ) | [inline] |
Definition at line 52 of file play_motion_test.cpp.
double PlayMotionTestClient::getJointPos | ( | const std::string & | joint_name | ) | [inline] |
Definition at line 70 of file play_motion_test.cpp.
void PlayMotionTestClient::jsCb | ( | const sensor_msgs::JointStatePtr & | js | ) | [inline, protected] |
Definition at line 100 of file play_motion_test.cpp.
int PlayMotionTestClient::playMotion | ( | const std::string & | motion_name, |
bool | skip_planning | ||
) | [inline] |
Definition at line 58 of file play_motion_test.cpp.
void PlayMotionTestClient::shouldFailWithCode | ( | int | code | ) | [inline] |
Definition at line 88 of file play_motion_test.cpp.
void PlayMotionTestClient::shouldFinishWith | ( | int | code, |
int | gstate | ||
) | [inline] |
Definition at line 82 of file play_motion_test.cpp.
void PlayMotionTestClient::shouldSucceed | ( | ) | [inline] |
Definition at line 93 of file play_motion_test.cpp.
ActionClientPtr PlayMotionTestClient::ac_ [private] |
Definition at line 106 of file play_motion_test.cpp.
ActionGoalStatePtr PlayMotionTestClient::gs_ [private] |
Definition at line 104 of file play_motion_test.cpp.
sensor_msgs::JointState PlayMotionTestClient::js_ [private] |
Definition at line 107 of file play_motion_test.cpp.
ros::Subscriber PlayMotionTestClient::js_sub_ [private] |
Definition at line 108 of file play_motion_test.cpp.
ros::NodeHandle PlayMotionTestClient::nh_ [private] |
Definition at line 105 of file play_motion_test.cpp.
int PlayMotionTestClient::ret_ [private] |
Definition at line 103 of file play_motion_test.cpp.