Go to the documentation of this file.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
00035
00036
00037 #include <pr2_arm_ik_action/trajectory_generation.h>
00038 #include <trajectory_msgs/JointTrajectory.h>
00039 #include <ros/ros.h>
00040 #include <iostream>
00041
00042 using namespace std;
00043
00044 void printTraj(const trajectory_msgs::JointTrajectory& traj)
00045 {
00046 cout << "Trajectory:" << endl;
00047 cout << " - Joints: " << endl;
00048 for (unsigned int i=0; i<traj.joint_names.size(); i++)
00049 cout << " - " << traj.joint_names[i] << endl;
00050 cout << " - Points: " << endl;
00051 for (unsigned int i=0; i<traj.points.size(); i++){
00052 cout << " - Time from start: " << traj.points[i].time_from_start.toSec()<< endl;
00053 cout << " - Positions: " << endl;
00054 for (unsigned int j=0; j<traj.points[i].positions.size(); j++)
00055 cout << " - " << traj.points[i].positions[j] << endl;
00056 cout << " - Velocities: " << endl;
00057 for (unsigned int j=0; j<traj.points[i].velocities.size(); j++)
00058 cout << " - " << traj.points[i].velocities[j] << endl;
00059 cout << " - Accelerations: " << endl;
00060 for (unsigned int j=0; j<traj.points[i].accelerations.size(); j++)
00061 cout << " - " << traj.points[i].accelerations[j] << endl;
00062 }
00063 }
00064
00065
00066
00067 int main(int argc, char** argv)
00068 {
00069 ros::init(argc, argv, "trajectory_generation_test");
00070
00071
00072 trajectory_msgs::JointTrajectory traj_in, traj_out;;
00073 traj_in.header.stamp = ros::Time::now();
00074 traj_in.joint_names.resize(3);
00075 traj_in.joint_names[0] = "wim1";
00076 traj_in.joint_names[1] = "wim2";
00077 traj_in.joint_names[2] = "wim3";
00078 traj_in.points.resize(3);
00079
00080 traj_in.points[0].positions.resize(3);
00081 traj_in.points[0].time_from_start = ros::Duration(1.0);
00082 traj_in.points[0].positions[0] = 0.0;
00083 traj_in.points[0].positions[1] = 0.0;
00084 traj_in.points[0].positions[2] = 0.0;
00085
00086 traj_in.points[1].positions.resize(3);
00087 traj_in.points[1].time_from_start = ros::Duration(2.0);
00088 traj_in.points[1].positions[0] = 1.0;
00089 traj_in.points[1].positions[1] = 1.0;
00090 traj_in.points[1].positions[2] = 1.0;
00091
00092 traj_in.points[2].positions.resize(3);
00093 traj_in.points[2].time_from_start = ros::Duration(2.0);
00094 traj_in.points[2].positions[0] = 2.0;
00095 traj_in.points[2].positions[1] = 2.0;
00096 traj_in.points[2].positions[2] = 2.0;
00097 printTraj(traj_in);
00098
00099
00100 trajectory::TrajectoryGenerator generator(0.1, 0.5, 3);
00101 generator.generate(traj_in, traj_out);
00102 printTraj(traj_out);
00103
00104 return 0;
00105 }