actionlib::SimpleClientGoalState getArmState() { return traj_client_elbow_flex_->getState(); }
//! Returns the current state of the action actionlib::SimpleClientGoalState getState() { return traj_client_->getState(); }
//send a desired joint trajectory to the joint trajectory action //and wait for it to finish bool execute_joint_trajectory(std::vector<double *> joint_trajectory) { int i, j; int trajectorylength = joint_trajectory.size(); //get the current joint angles double current_angles[6]; get_current_joint_angles(current_angles); //fill the goal message with the desired joint trajectory goal.trajectory.points.resize(trajectorylength+1); //set the first trajectory point to the current position goal.trajectory.points[0].positions.resize(6); goal.trajectory.points[0].velocities.resize(6); for(j=0; j<6; j++) { goal.trajectory.points[0].positions[j] = current_angles[j]; goal.trajectory.points[0].velocities[j] = 0.0; } //make the first trajectory point start 0.25 seconds from when we run goal.trajectory.points[0].time_from_start = ros::Duration(0.25); //fill in the rest of the trajectory double time_from_start = 0.25; for(i=0; i<trajectorylength; i++) { goal.trajectory.points[i+1].positions.resize(6); goal.trajectory.points[i+1].velocities.resize(6); //fill in the joint positions (velocities of 0 mean that the arm //will try to stop briefly at each waypoint) for(j=0; j<6; j++) { goal.trajectory.points[i+1].positions[j] = joint_trajectory[i][j]; goal.trajectory.points[i+1].velocities[j] = 0.0; } //compute a desired time for this trajectory point using a max //joint velocity double max_joint_move = 0; for(j=0; j<6; j++) { double joint_move = fabs(goal.trajectory.points[i+1].positions[j] - goal.trajectory.points[i].positions[j]); if(joint_move > max_joint_move) max_joint_move = joint_move; } double seconds = max_joint_move/MAX_JOINT_VEL; ROS_INFO("max_joint_move: %0.3f, seconds: %0.3f", max_joint_move, seconds); time_from_start += seconds; goal.trajectory.points[i+1].time_from_start = ros::Duration(time_from_start); } //when to start the trajectory goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(0.25); ROS_INFO("Sending goal to joint_trajectory_action"); action_client->sendGoal(goal); action_client->waitForResult(); //get the current joint angles for debugging get_current_joint_angles(current_angles); // ROS_INFO("joint angles after trajectory: %0.3f %0.3f %0.3f %0.3f %0.3f %0.3f %0.3f\n",current_angles[0],current_angles[1],current_angles[2],current_angles[3],current_angles[4],current_angles[5]); if(action_client->getState() == actionlib::SimpleClientGoalState::SUCCEEDED){ ROS_INFO("Hooray, the arm finished the trajectory!"); return 1; } ROS_INFO("The arm failed to execute the trajectory."); return 0; }