31 Reading Trajectory Data from CSV and Send To Robot via Action Client 43 from control_msgs.msg
import (
44 FollowJointTrajectoryAction,
45 FollowJointTrajectoryGoal,
47 from trajectory_msgs.msg
import (
53 print(
"Initializing node... ")
54 rospy.init_node(
"joint_trajectory_client_csv_example")
56 print(
"Running. Ctrl-c to quit")
59 goal = FollowJointTrajectoryGoal()
60 goal.goal_time_tolerance = rospy.Time(1)
62 with open(filename)
as f:
63 reader = csv.reader(f, skipinitialspace=
True)
67 goal.trajectory.joint_names = row[1:]
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,
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")
85 goal.trajectory.header.stamp = rospy.Time.now()
86 client.send_goal(goal)
88 if not client.wait_for_result(timeout=rospy.Duration(60)):
89 rospy.logerr(
"Timed out waiting for JTA")
90 rospy.loginfo(
"Exitting...")
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])