test_arm_trajectory_controller.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 the 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 
35 #include <ros/node.h>
36 #include <manipulation_msgs/JointTraj.h>
37 
38 static int done = 0;
39 
40 void finalize(int donecare)
41 {
42  done = 1;
43 }
44 
45 int main( int argc, char** argv )
46 {
47 
48  /*********** Initialize ROS ****************/
49  ros::init(argc,argv);
50  ros::Node *node = new ros::Node("test_arm_trajectory_controller");
51 
52  signal(SIGINT, finalize);
53  signal(SIGQUIT, finalize);
54  signal(SIGTERM, finalize);
55 
56 
57  /*********** Start moving the robot ************/
58  manipulation_msgs::JointTraj cmd;
59 
60  int num_points = 3;
61  int num_joints = 14;
62 
63  cmd.set_points_size(num_points);
64 
65  for(int i=0; i<num_points; i++)
66  {
67  cmd.points[i].set_positions_size(num_joints);
68  for(int j=0; j < num_joints; j++)
69  {
70  cmd.points[i].positions[j] = 0.0;
71  }
72  }
73 
74 /*
75  cmd.points[0].positions[0] = 0.0;
76  cmd.points[0].positions[1] = 0.0;
77  cmd.points[0].positions[2] = 0.0;
78  cmd.points[0].positions[3] = 0.0;
79  cmd.points[0].positions[4] = 0.0;
80  cmd.points[0].positions[5] = 0.0;
81  cmd.points[0].positions[6] = 0.0;
82  cmd.points[0].time = 0.0;
83 */
84 
85  cmd.points[0].positions[0] = 0.5;
86  cmd.points[0].positions[1] = 0.5;
87  cmd.points[0].positions[2] = 0.2;
88  cmd.points[0].positions[3] = -0.5;
89  cmd.points[0].positions[4] = 0.4;
90  cmd.points[0].positions[5] = 0.0;
91  cmd.points[0].positions[6] = 0.0;
92  cmd.points[0].time = 0.0;
93 
94  cmd.points[1].positions[0] = 0.0;
95  cmd.points[1].positions[1] = 0.0;
96  cmd.points[1].positions[2] = 0.0;
97  cmd.points[1].positions[3] = 0.0;
98  cmd.points[1].positions[4] = 0.0;
99  cmd.points[1].positions[5] = 0.0;
100  cmd.points[1].positions[6] = 0.0;
101  cmd.points[1].time = 0.0;
102 
103  cmd.points[2].positions[0] = -0.5;
104  cmd.points[2].positions[1] = 0.3;
105  cmd.points[2].positions[2] = 0.2;
106  cmd.points[2].positions[3] = -1.0;
107  cmd.points[2].positions[4] = -0.4;
108  cmd.points[2].positions[5] = 0.0;
109  cmd.points[2].positions[6] = 0.0;
110  cmd.points[2].time = 0.0;
111 
112  node->advertise<manipulation_msgs::JointTraj>("/arm/trajectory_controller/arm_trajectory_command",1);
113  node->publish("/arm/trajectory_controller/arm_trajectory_command",cmd);
114  sleep(4);
115 
116  ros::Time start_time = ros::Time::now();
117  ros::Duration sleep_time = ros::Duration().fromSec(0.01);
118 
119 }
void finalize(int donecare)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Duration & fromSec(double t)
static Time now()


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Wed Jun 5 2019 19:34:08