$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * Author: Wim Meeussen 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 // create test trajectory 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 // create trajectory generator 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 }