test_careobot_st_jla_ca_selfcollision_arm_left_internal_motion.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.NUM_FILT, False)
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  cli.set_config_param(tcc.EPS_TRUNC, 0.001)
43 
44  cli.set_config_param(tcc.PRIO_CA, 50)
45  cli.set_config_param(tcc.PRIO_JLA, 100) # change priorities now CA constraint has highest prio
46 
47  cli.set_config_param(tcc.SOLVER, tcc.TwistController_STACK_OF_TASKS)
48  cli.set_config_param(tcc.K_H, 1.0)
49 
50  cli.set_config_param(tcc.CONSTR_CA, tcc.TwistController_CA)
51  cli.set_config_param(tcc.K_H_CA, -1.0)
52  cli.set_config_param(tcc.DAMP_CA, 0.000001)
53  cli.set_config_param(tcc.ACTIV_THRESH_CA, 0.1)
54  cli.set_config_param(tcc.ACTIV_BUF_CA, 50.0)
55  cli.set_config_param(tcc.CRIT_THRESH_CA, 0.03)
56 
57  cli.set_config_param(tcc.CONSTR_JLA, tcc.TwistController_JLA)
58  cli.set_config_param(tcc.K_H_JLA, -1.0)
59  cli.set_config_param(tcc.DAMP_JLA, 0.000001)
60  cli.set_config_param(tcc.ACTIV_THRESH_JLA, 10.0)
61  cli.set_config_param(tcc.ACTIV_BUF_JLA, 300.0)
62  cli.set_config_param(tcc.CRIT_THRESH_JLA, 5.0)
63 
64  cli.set_config_param(tcc.KIN_EXT, tcc.TwistController_NO_EXTENSION)
65  cli.set_config_param(tcc.KEEP_DIR, True)
66  cli.set_config_param(tcc.ENF_VEL_LIM, True)
67  cli.set_config_param(tcc.ENF_POS_LIM, True)
68 
69  cli.update()
70  cli.close()
71 
72  cli = Client('frame_tracker')
73  ft_param = {'cart_min_dist_threshold_lin' : 0.2, 'cart_min_dist_threshold_rot' : 0.2}
74  cli.update_configuration(ft_param)
75  cli.close()
76 
77 
78 def init_pos():
79  sss = simple_script_server()
80  # sss.move("arm_right", [[-0.039928546971938594, 0.7617065276699337, 0.01562043859727158, -1.7979678396373568, 0.013899422367821046, 1.0327319085987252, 0.021045294231647915]])
81  sss.move("arm_left", [[-0.17566952192977148, 0.6230441162870415, 0.27476319388433623, -1.1163222472275676, 0.3166667900974902, 0.5333301416131739, -0.32441227738211875], ])
82 
83 
84 if __name__ == "__main__":
85  rospy.init_node("test_careobot_st_jla_ca_selfcollision_arm_left")
86 
87  base_dir = '/home/fxm-mb/bag-files/arm_left_selfcollision/'
88  if rospy.has_param('~base_dir'):
89  base_dir = rospy.get_param('~base_dir')
90  else:
91  rospy.logwarn('Could not find parameter ~base_dir. Using default base_dir: ' + base_dir)
92 
93  if rospy.has_param('chain_tip_link'):
94  chain_tip_link = rospy.get_param('chain_tip_link')
95  else:
96  rospy.logwarn('Could not find parameter chain_tip_link.')
97  exit(-1)
98 
99  if rospy.has_param('frame_tracker/tracking_frame'):
100  tracking_frame = rospy.get_param('frame_tracker/tracking_frame')
101  else:
102  rospy.logwarn('Could not find parameter frame_tracker/tracking_frame.')
103  exit(-2)
104 
105  if rospy.has_param('root_frame'):
106  root_frame = rospy.get_param('root_frame')
107  else:
108  rospy.logwarn('Could not find parameter root_frame.')
109  exit(-3)
110 
111  t = time.localtime()
112  launch_time_stamp = time.strftime("%Y%m%d_%H_%M_%S", t)
113  command = 'rosbag play ' + base_dir + 'arm_left_to_head_internal_motions.bag'
114 
115  data_krakens = [
116  JointStateDataKraken(base_dir + 'internal_motion_joint_state_data_' + launch_time_stamp + '.csv'),
117  ObstacleDistanceDataKraken(base_dir + 'internal_motion_obst_dist_data_' + launch_time_stamp + '.csv'),
118  TwistDataKraken(base_dir + 'internal_motion_twist_data_' + launch_time_stamp + '.csv'),
119  JointVelocityDataKraken(base_dir + 'internal_motion_joint_vel_data_' + launch_time_stamp + '.csv'),
120  FrameTrackingDataKraken(base_dir + 'internal_motion_frame_tracking_data_' + launch_time_stamp + '.csv', root_frame, chain_tip_link, tracking_frame), ]
121 
122  init_pos()
124 
125 
126 
127 # exit()
128 
129 
130  status_open = True
131  for data_kraken in data_krakens:
132  status_open = status_open and data_kraken.open()
133  if status_open:
134  rospy.loginfo('Subscribers started for data collection ... \nPress CTRL+C to stop program and write data to the file.')
135  pid = subprocess.Popen(command, stdin = subprocess.PIPE, cwd = base_dir, shell = True)
136  time.sleep(0.5) # give time to switch mode back
137  rate = rospy.Rate(10)
138  try:
139  while not rospy.is_shutdown():
140  rate.sleep()
141  if(pid.poll() is not None):
142  rospy.loginfo('Bag file finished stop script.')
143  break
144 
145  except (KeyboardInterrupt, SystemExit) as e:
146  rospy.loginfo('KeyboardInterrupt / SystemExit: ' + str(e))
147  # save data
148  for data_kraken in data_krakens:
149  data_kraken.writeAllData()
150  except:
151  rospy.logerr('Else exception.')
152  else:
153  for data_kraken in data_krakens:
154  data_kraken.writeAllData()
155  try:
156  # pid.send_signal(signal.SIGINT)
157  pid.kill()
158  pid.send_signal(signal.SIGINT)
159  except Exception as e:
160  rospy.logerr('Failed to stop rosbag play due to exception: ' + str(e))
161  else:
162  rospy.logerr('Failed to open DataKraken files.')
163 
164 


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