test_careobot_GPM_jla_ca_torus.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 subprocess
22 
23 from simple_script_server import simple_script_server ## pylint: disable=no-name-in-module
24 import twist_controller_config as tcc
25 from dynamic_reconfigure.client import Client
26 
27 from data_collection import JointStateDataKraken
28 from data_collection import ObstacleDistanceDataKraken
29 from data_collection import TwistDataKraken
30 from data_collection import JointVelocityDataKraken
31 from data_collection import FrameTrackingDataKraken
32 
33 # has to be startet with ns param: rosrun cob_twist_controller collect_twist_control_eval_data.py __ns:=arm_right
35  cli = tcc.TwistControllerReconfigureClient()
36  cli.init()
37 
38  cli.set_config_param(tcc.DAMP_METHOD, tcc.TwistController_MANIPULABILITY)
39  cli.set_config_param(tcc.LAMBDA_MAX, 0.1)
40  cli.set_config_param(tcc.W_THRESH, 0.05)
41 
42  cli.set_config_param(tcc.PRIO_CA, 100)
43  cli.set_config_param(tcc.PRIO_JLA, 50)
44 
45  cli.set_config_param(tcc.SOLVER, tcc.TwistController_GPM)
46  cli.set_config_param(tcc.K_H, 1.0)
47 
48  cli.set_config_param(tcc.CONSTR_CA, tcc.TwistController_CA)
49  cli.set_config_param(tcc.K_H_CA, -2.0)
50  cli.set_config_param(tcc.DAMP_CA, 0.000001)
51  cli.set_config_param(tcc.ACTIV_THRESH_CA, 0.1)
52 
53  cli.set_config_param(tcc.CONSTR_JLA, tcc.TwistController_JLA)
54  cli.set_config_param(tcc.K_H_JLA, -1.0)
55  cli.set_config_param(tcc.DAMP_JLA, 0.00001)
56  cli.set_config_param(tcc.ACTIV_THRESH_JLA, 10.0)
57 
58  cli.set_config_param(tcc.KIN_EXT, tcc.TwistController_NO_EXTENSION)
59  cli.set_config_param(tcc.KEEP_DIR, True)
60  cli.set_config_param(tcc.ENF_VEL_LIM, True)
61  cli.set_config_param(tcc.ENF_POS_LIM, False) # To show that joint pos limits are violated if possible.
62 
63  cli.update()
64  cli.close()
65 
66  cli = Client('frame_tracker')
67  ft_param = {'cart_min_dist_threshold_lin' : 0.2, 'cart_min_dist_threshold_rot' : 0.2}
68  cli.update_configuration(ft_param)
69  cli.close()
70 
71 
72 def init_pos():
73  sss = simple_script_server()
74  sss.move("arm_right", "home")
75  sss.move("arm_right", [[-0.039928546971938594, 0.7617065276699337, 0.01562043859727158, -1.7979678396373568, 0.013899422367821046, 1.0327319085987252, 0.021045294231647915]])
76 
77 
78 if __name__ == "__main__":
79  rospy.init_node("test_careobot_st_jla_ca_torus")
80 
81  base_dir = '/home/fxm-mb/bag-files/2015_08_06/'
82  if rospy.has_param('~base_dir'):
83  base_dir = rospy.get_param('~base_dir')
84  else:
85  rospy.logwarn('Could not find parameter ~base_dir. Using default base_dir: ' + base_dir)
86 
87  if rospy.has_param('chain_tip_link'):
88  chain_tip_link = rospy.get_param('chain_tip_link')
89  else:
90  rospy.logwarn('Could not find parameter chain_tip_link.')
91  exit(-1)
92 
93  if rospy.has_param('frame_tracker/tracking_frame'):
94  tracking_frame = rospy.get_param('frame_tracker/tracking_frame')
95  else:
96  rospy.logwarn('Could not find parameter frame_tracker/tracking_frame.')
97  exit(-2)
98 
99  if rospy.has_param('root_frame'):
100  root_frame = rospy.get_param('root_frame')
101  else:
102  rospy.logwarn('Could not find parameter root_frame.')
103  exit(-3)
104 
105  t = time.localtime()
106  launch_time_stamp = time.strftime("%Y%m%d_%H_%M_%S", t)
107  command = 'rosbag play ' + base_dir + 'careobot_st_jla_ca.bag'
108 
109  data_krakens = [
110  JointStateDataKraken(base_dir + 'careobot_GPM_jla_ca_joint_state_data_' + launch_time_stamp + '.csv'),
111  ObstacleDistanceDataKraken(base_dir + 'careobot_GPM_jla_ca_obst_dist_data_' + launch_time_stamp + '.csv'),
112  TwistDataKraken(base_dir + 'careobot_GPM_jla_ca_twist_data_' + launch_time_stamp + '.csv'),
113  JointVelocityDataKraken(base_dir + 'careobot_GPM_jla_ca_joint_vel_data_' + launch_time_stamp + '.csv'),
114  FrameTrackingDataKraken(base_dir + 'careobot_GPM_jla_ca_frame_tracking_data_' + launch_time_stamp + '.csv', root_frame, chain_tip_link, tracking_frame), ]
115 
116  init_pos()
118 
119  status_open = True
120  for data_kraken in data_krakens:
121  status_open = status_open and data_kraken.open()
122  if status_open:
123  rospy.loginfo('Subscribers started for data collection ... \nPress CTRL+C to stop program and write data to the file.')
124 
125  traj_marker_command = 'rosrun cob_twist_controller debug_trajectory_marker_node __ns:=' + rospy.get_namespace()
126  traj_marker_pid = subprocess.Popen(traj_marker_command, stdin = subprocess.PIPE, shell = True)
127  pid = subprocess.Popen(command, stdin = subprocess.PIPE, cwd = base_dir, shell = True)
128 
129  # pid.wait()
130  time.sleep(1.5) # give time to switch mode back
131 
132  if traj_marker_pid.poll() is not None:
133  rospy.logerr("traj_marker_pid returned code. Aborting ...")
134  pid.send_signal(signal.SIGINT)
135  pid.kill()
136  # traj_marker_pid.send_signal(signal.SIGINT)
137  traj_marker_pid.send_signal(signal.SIGTERM)
138  traj_marker_pid.kill()
139  exit()
140 
141  time.sleep(0.5) # give time to switch mode back
142 
143  rate = rospy.Rate(10)
144  try:
145  while not rospy.is_shutdown():
146  rate.sleep()
147  if(pid.poll() is not None):
148  rospy.loginfo('Bag file finished stop script.')
149  break
150 
151  except (KeyboardInterrupt, SystemExit) as e:
152  rospy.loginfo('KeyboardInterrupt / SystemExit: ' + str(e))
153  # save data
154  for data_kraken in data_krakens:
155  data_kraken.writeAllData()
156  except:
157  rospy.logerr('Else exception.')
158  else:
159  for data_kraken in data_krakens:
160  data_kraken.writeAllData()
161 
162  try:
163  # pid.send_signal(signal.SIGINT)
164  pid.kill()
165  pid.send_signal(signal.SIGINT)
166  except Exception as e:
167  rospy.logerr('Failed to stop rosbag play due to exception: ' + str(e))
168  try:
169  traj_marker_pid.kill()
170  traj_marker_pid.send_signal(signal.SIGINT)
171  except Exception as e:
172  rospy.logerr('Failed to stop debug_trajectory_marker_node due to exception: ' + str(e))
173  else:
174  rospy.logerr('Failed to open DataKraken files.')
175 
176 
177 
178 
179 
180 
181 


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