joint_trajectory_client_csv.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2019, 2020 Naoki Hiraoka
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 #
9 # 1. Redistributions of source code must retain the above copyright notice,
10 # this list of conditions and the following disclaimer.
11 # 2. Redistributions in binary form must reproduce the above copyright
12 # notice, this list of conditions and the following disclaimer in the
13 # documentation and/or other materials provided with the distribution.
14 # 3. Neither the name of the Rethink Robotics nor the names of its
15 # contributors may be used to endorse or promote products derived from
16 # this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 # POSSIBILITY OF SUCH DAMAGE.
29 
30 """
31 Reading Trajectory Data from CSV and Send To Robot via Action Client
32 """
33 
34 import rospy
35 
36 import actionlib
37 
38 import argparse
39 import sys
40 import time
41 import csv
42 
43 from control_msgs.msg import (
44  FollowJointTrajectoryAction,
45  FollowJointTrajectoryGoal,
46 )
47 from trajectory_msgs.msg import (
48  JointTrajectoryPoint,
49 )
50 
51 
52 def main(filename):
53  print("Initializing node... ")
54  rospy.init_node("joint_trajectory_client_csv_example")
55  rospy.sleep(1)
56  print("Running. Ctrl-c to quit")
57 
58  # init goal
59  goal = FollowJointTrajectoryGoal()
60  goal.goal_time_tolerance = rospy.Time(1)
61 
62  with open(filename) as f:
63  reader = csv.reader(f, skipinitialspace=True)
64  first_row = True
65  for row in reader:
66  if first_row:
67  goal.trajectory.joint_names = row[1:]
68  first_row = False
69  else:
70  point = JointTrajectoryPoint()
71  point.positions = [float(n) for n in row[1:]]
72  point.time_from_start = rospy.Duration(float(row[0]))
73  goal.trajectory.points.append(point)
75  '/fullbody_controller/follow_joint_trajectory',
76  FollowJointTrajectoryAction,
77  )
78 
79  if not client.wait_for_server(timeout=rospy.Duration(10)):
80  rospy.logerr("Timed out waiting for Action Server")
81  rospy.signal_shutdown("Timed out waiting for Action Server")
82  sys.exit(1)
83 
84  # send goal
85  goal.trajectory.header.stamp = rospy.Time.now()
86  client.send_goal(goal)
87  print("waiting...")
88  if not client.wait_for_result(timeout=rospy.Duration(60)):
89  rospy.logerr("Timed out waiting for JTA")
90  rospy.loginfo("Exitting...")
91 
92 
93 if __name__ == "__main__":
94  parser = argparse.ArgumentParser(description='Reading CSV trajectory data and send to the robot.')
95  parser.add_argument('filename', type=str, nargs=1,
96  help='CSV trajectory data file name')
97  args = parser.parse_args(rospy.myargv()[1:])
98  main(args.filename[0])


gundam_rx78_control
Author(s): Kei Okada , Naoki Hiraoka
autogenerated on Wed Sep 2 2020 03:33:33