37 #include <pr2_arm_ik_action/trajectory_generation.h> 38 #include <trajectory_msgs/JointTrajectory.h> 44 void printTraj(
const trajectory_msgs::JointTrajectory& traj)
46 cout <<
"Trajectory:" << endl;
47 cout <<
" - Joints: " << endl;
48 for (
unsigned int i=0; i<traj.joint_names.size(); i++)
49 cout <<
" - " << traj.joint_names[i] << endl;
50 cout <<
" - Points: " << endl;
51 for (
unsigned int i=0; i<traj.points.size(); i++){
52 cout <<
" - Time from start: " << traj.points[i].time_from_start.toSec()<< endl;
53 cout <<
" - Positions: " << endl;
54 for (
unsigned int j=0; j<traj.points[i].positions.size(); j++)
55 cout <<
" - " << traj.points[i].positions[j] << endl;
56 cout <<
" - Velocities: " << endl;
57 for (
unsigned int j=0; j<traj.points[i].velocities.size(); j++)
58 cout <<
" - " << traj.points[i].velocities[j] << endl;
59 cout <<
" - Accelerations: " << endl;
60 for (
unsigned int j=0; j<traj.points[i].accelerations.size(); j++)
61 cout <<
" - " << traj.points[i].accelerations[j] << endl;
67 int main(
int argc,
char** argv)
69 ros::init(argc, argv,
"trajectory_generation_test");
72 trajectory_msgs::JointTrajectory traj_in, traj_out;;
74 traj_in.joint_names.resize(3);
75 traj_in.joint_names[0] =
"wim1";
76 traj_in.joint_names[1] =
"wim2";
77 traj_in.joint_names[2] =
"wim3";
78 traj_in.points.resize(3);
80 traj_in.points[0].positions.resize(3);
82 traj_in.points[0].positions[0] = 0.0;
83 traj_in.points[0].positions[1] = 0.0;
84 traj_in.points[0].positions[2] = 0.0;
86 traj_in.points[1].positions.resize(3);
88 traj_in.points[1].positions[0] = 1.0;
89 traj_in.points[1].positions[1] = 1.0;
90 traj_in.points[1].positions[2] = 1.0;
92 traj_in.points[2].positions.resize(3);
94 traj_in.points[2].positions[0] = 2.0;
95 traj_in.points[2].positions[1] = 2.0;
96 traj_in.points[2].positions[2] = 2.0;
101 generator.
generate(traj_in, traj_out);
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
void printTraj(const trajectory_msgs::JointTrajectory &traj)
void generate(const trajectory_msgs::JointTrajectory &traj_in, trajectory_msgs::JointTrajectory &traj_out)