trajectory_generation_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * Author: Wim Meeussen
35  *********************************************************************/
36 
37 #include <pr2_arm_ik_action/trajectory_generation.h>
38 #include <trajectory_msgs/JointTrajectory.h>
39 #include <ros/ros.h>
40 #include <iostream>
41 
42 using namespace std;
43 
44 void printTraj(const trajectory_msgs::JointTrajectory& traj)
45 {
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;
62  }
63 }
64 
65 
66 
67 int main(int argc, char** argv)
68 {
69  ros::init(argc, argv, "trajectory_generation_test");
70 
71  // create test trajectory
72  trajectory_msgs::JointTrajectory traj_in, traj_out;;
73  traj_in.header.stamp = ros::Time::now();
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);
79 
80  traj_in.points[0].positions.resize(3);
81  traj_in.points[0].time_from_start = ros::Duration(1.0);
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;
85 
86  traj_in.points[1].positions.resize(3);
87  traj_in.points[1].time_from_start = ros::Duration(2.0);
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;
91 
92  traj_in.points[2].positions.resize(3);
93  traj_in.points[2].time_from_start = ros::Duration(2.0);
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;
97  printTraj(traj_in);
98 
99  // create trajectory generator
100  trajectory::TrajectoryGenerator generator(0.1, 0.5, 3);
101  generator.generate(traj_in, traj_out);
102  printTraj(traj_out);
103 
104  return 0;
105 }
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)
static Time now()


pr2_arm_move_ik
Author(s): Wim Meeusen, Melonee Wise
autogenerated on Fri Jun 7 2019 22:06:41