test_careobot_st_jla_ca_sphere.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import time
19 import rospy
20 import signal
21 import six
22 import subprocess
23 
24 from simple_script_server import simple_script_server ## pylint: disable=no-name-in-module
25 import twist_controller_config as tcc
26 from dynamic_reconfigure.client import Client
27 
28 from data_collection import JointStateDataKraken
29 from data_collection import ObstacleDistanceDataKraken
30 from data_collection import TwistDataKraken
31 from data_collection import JointVelocityDataKraken
32 from data_collection import FrameTrackingDataKraken
33 
34 # has to be startet with ns param: rosrun cob_twist_controller collect_twist_control_eval_data.py __ns:=arm_right
36  cli = tcc.TwistControllerReconfigureClient()
37  cli.init()
38 
39  cli.set_config_param(tcc.DAMP_METHOD, tcc.TwistController_MANIPULABILITY)
40  cli.set_config_param(tcc.LAMBDA_MAX, 0.1)
41  cli.set_config_param(tcc.W_THRESH, 0.05)
42 
43  cli.set_config_param(tcc.PRIO_CA, 100)
44  cli.set_config_param(tcc.PRIO_JLA, 50)
45 
46  cli.set_config_param(tcc.SOLVER, tcc.TwistController_STACK_OF_TASKS)
47  cli.set_config_param(tcc.K_H, 1.0)
48 
49  cli.set_config_param(tcc.CONSTR_CA, tcc.TwistController_CA)
50  cli.set_config_param(tcc.K_H_CA, -2.0)
51  cli.set_config_param(tcc.ACTIV_THRESH_CA, 0.1)
52  cli.set_config_param(tcc.ACTIV_BUF_CA, 50.0)
53  cli.set_config_param(tcc.CRIT_THRESH_CA, 0.025)
54  cli.set_config_param(tcc.DAMP_CA, 0.000001)
55 
56  cli.set_config_param(tcc.CONSTR_JLA, tcc.TwistController_JLA)
57  cli.set_config_param(tcc.K_H_JLA, -1.0)
58  cli.set_config_param(tcc.ACTIV_THRESH_JLA, 10.0)
59  cli.set_config_param(tcc.ACTIV_BUF_JLA, 300.0)
60  cli.set_config_param(tcc.CRIT_THRESH_JLA, 5.0)
61  cli.set_config_param(tcc.DAMP_JLA, 0.00001)
62 
63  cli.set_config_param(tcc.KIN_EXT, tcc.TwistController_NO_EXTENSION)
64  cli.set_config_param(tcc.KEEP_DIR, True)
65  cli.set_config_param(tcc.ENF_VEL_LIM, True)
66  cli.set_config_param(tcc.ENF_POS_LIM, True)
67 
68  cli.update()
69  cli.close()
70 
71  cli = Client('frame_tracker')
72  ft_param = {'cart_min_dist_threshold_lin' : 0.2, 'cart_min_dist_threshold_rot' : 0.2}
73  cli.update_configuration(ft_param)
74  cli.close()
75 
76 
77 def init_pos():
78  sss = simple_script_server()
79  sss.move("arm_right", "home")
80 
81 
82 if __name__ == "__main__":
83  rospy.init_node("test_careobot_st_jla_ca_sphere")
84 
85  base_dir = ''
86  if rospy.has_param('~base_dir'):
87  base_dir = rospy.get_param('~base_dir')
88  else:
89  rospy.logwarn('Could not find parameter ~base_dir.')
90  base_dir = six.moves.input("Enter name of bagfile base_dir: ")
91 
92  if rospy.has_param('chain_tip_link'):
93  chain_tip_link = rospy.get_param('chain_tip_link')
94  else:
95  rospy.logwarn('Could not find parameter chain_tip_link.')
96  exit(-1)
97 
98  if rospy.has_param('frame_tracker/target_frame'):
99  tracking_frame = rospy.get_param('frame_tracker/target_frame')
100  else:
101  rospy.logwarn('Could not find parameter frame_tracker/tracking_frame.')
102  exit(-2)
103 
104  if rospy.has_param('root_frame'):
105  root_frame = rospy.get_param('root_frame')
106  else:
107  rospy.logwarn('Could not find parameter root_frame.')
108  exit(-3)
109 
110  t = time.localtime()
111  launch_time_stamp = time.strftime("%Y%m%d_%H_%M_%S", t)
112 
113  command = 'rosbag play ' + base_dir + 'careobot_st_jla_ca_sphere.bag'
114  # command = 'rosbag play -u 10 ' + base_dir + 'careobot_st_jla_ca_sphere.bag'
115 
116  data_krakens = [
117  JointStateDataKraken(base_dir + 'joint_state_data_' + launch_time_stamp + '.csv'),
118  ObstacleDistanceDataKraken(base_dir + 'obst_dist_data_' + launch_time_stamp + '.csv'),
119  TwistDataKraken(base_dir + 'twist_data_' + launch_time_stamp + '.csv'),
120  JointVelocityDataKraken(base_dir + 'joint_vel_data_' + launch_time_stamp + '.csv'),
121  FrameTrackingDataKraken(base_dir + 'frame_tracking_data_' + launch_time_stamp + '.csv', root_frame, chain_tip_link, tracking_frame), ]
122 
123  init_pos()
125 
126  status_open = True
127  for data_kraken in data_krakens:
128  status_open = status_open and data_kraken.open()
129  if status_open:
130  rospy.loginfo('Subscribers started for data collection ... \nPress CTRL+C to stop program and write data to the file.')
131 
132  traj_marker_command = 'rosrun cob_twist_controller debug_trajectory_marker_node __ns:=' + rospy.get_namespace()
133  traj_marker_pid = subprocess.Popen(traj_marker_command, stdin = subprocess.PIPE, shell = True)
134  pid = subprocess.Popen(command, stdin = subprocess.PIPE, cwd = base_dir, shell = True)
135 
136  # pid.wait()
137  time.sleep(1.5) # give time to switch mode back
138 
139  if traj_marker_pid.poll() is not None:
140  rospy.logerr("traj_marker_pid returned code. Aborting ...")
141  pid.send_signal(signal.SIGINT)
142  pid.kill()
143  # traj_marker_pid.send_signal(signal.SIGINT)
144  traj_marker_pid.send_signal(signal.SIGTERM)
145  traj_marker_pid.kill()
146  exit()
147 
148  time.sleep(0.5) # give time to switch mode back
149 
150  rate = rospy.Rate(10)
151  try:
152  while not rospy.is_shutdown():
153  rate.sleep()
154  if(pid.poll() is not None):
155  rospy.loginfo('Bag file finished stop script.')
156  break
157 
158  except (KeyboardInterrupt, SystemExit) as e:
159  rospy.loginfo('KeyboardInterrupt / SystemExit: ' + str(e))
160  # save data
161  for data_kraken in data_krakens:
162  data_kraken.writeAllData()
163  except:
164  rospy.logerr('Else exception.')
165  else:
166  for data_kraken in data_krakens:
167  data_kraken.writeAllData()
168 
169  try:
170  # pid.send_signal(signal.SIGINT)
171  pid.kill()
172  pid.send_signal(signal.SIGINT)
173  except Exception as e:
174  rospy.logerr('Failed to stop rosbag play due to exception: ' + str(e))
175  try:
176  traj_marker_pid.kill()
177  traj_marker_pid.send_signal(signal.SIGINT)
178  except Exception as e:
179  rospy.logerr('Failed to stop debug_trajectory_marker_node due to exception: ' + str(e))
180  else:
181  rospy.logerr('Failed to open DataKraken files.')
182 
183 
184 
185 
186 
187 
188 


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:01