00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include <ros/ros.h>
00038 #include <actionlib/client/simple_action_client.h>
00039 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00040
00041 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::JointTrajectoryAction> JointExecutorActionClient;
00042
00043 void spinThread()
00044 {
00045 ros::spin();
00046 }
00047
00048 int main(int argc, char** argv)
00049 {
00050 ros::init(argc, argv, "test_controller");
00051 boost::thread spin_thread(&spinThread);
00052 JointExecutorActionClient *traj_action_client_ = new JointExecutorActionClient("collision_free_arm_trajectory_action_right_arm");
00053
00054 while(!traj_action_client_->waitForServer(ros::Duration(1.0))){
00055 ROS_INFO("Waiting for the joint_trajectory_action action server to come up");
00056 if(!ros::ok()) {
00057 exit(0);
00058 }
00059 }
00060
00061 pr2_controllers_msgs::JointTrajectoryGoal goal;
00062 goal.trajectory.joint_names.push_back("r_shoulder_pan_joint");
00063 goal.trajectory.joint_names.push_back("r_shoulder_lift_joint");
00064 goal.trajectory.joint_names.push_back("r_upper_arm_roll_joint");
00065 goal.trajectory.joint_names.push_back("r_elbow_flex_joint");
00066 goal.trajectory.joint_names.push_back("r_forearm_roll_joint");
00067 goal.trajectory.joint_names.push_back("r_wrist_flex_joint");
00068 goal.trajectory.joint_names.push_back("r_wrist_roll_joint");
00069
00070 goal.trajectory.points.resize(1);
00071 for(unsigned int i=0; i < 7; i++)
00072 goal.trajectory.points[0].positions.push_back(0.0);
00073 goal.trajectory.points[0].positions[0] = 0.0;
00074 goal.trajectory.points[0].positions[0] = -1.57/2.0;
00075 goal.trajectory.points[0].time_from_start = ros::Duration(0.0);
00076
00077 traj_action_client_->sendGoal(goal);
00078 ROS_INFO("Sent goal");
00079
00080 while(!traj_action_client_->getState().isDone() && ros::ok())
00081 {
00082 ros::Duration(0.1).sleep();
00083 }
00084 return 0;
00085 }