test_careobot_base.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 controller_manager_msgs.srv import SwitchController
24 
25 from simple_script_server import simple_script_server ## pylint: disable=no-name-in-module
26 import twist_controller_config as tcc
27 from dynamic_reconfigure.client import Client
28 
29 from data_collection import JointStateDataKraken
30 from data_collection import ObstacleDistanceDataKraken
31 from data_collection import TwistDataKraken
32 from data_collection import JointVelocityDataKraken
33 from data_collection import FrameTrackingDataKraken
34 from data_collection import OdometryDataKraken
35 
36 # has to be startet with ns param: rosrun cob_twist_controller collect_twist_control_eval_data.py __ns:=arm_right
38  cli = tcc.TwistControllerReconfigureClient()
39  cli.init()
40 
41  cli.set_config_param(tcc.NUM_FILT, False)
42  cli.set_config_param(tcc.DAMP_METHOD, tcc.TwistController_CONSTANT)
43  cli.set_config_param(tcc.DAMP_FACT, 0.2)
44  cli.set_config_param(tcc.EPS_TRUNC, 0.001)
45 
46  cli.set_config_param(tcc.PRIO_CA, 100)
47  cli.set_config_param(tcc.PRIO_JLA, 50)
48 
49  cli.set_config_param(tcc.SOLVER, tcc.TwistController_STACK_OF_TASKS)
50  cli.set_config_param(tcc.K_H, 1.0)
51 
52  cli.set_config_param(tcc.CONSTR_CA, tcc.TwistController_CA)
53  cli.set_config_param(tcc.K_H_CA, -1.0)
54  cli.set_config_param(tcc.ACTIV_THRESH_CA, 0.1)
55  cli.set_config_param(tcc.ACTIV_BUF_CA, 25.0)
56  cli.set_config_param(tcc.CRIT_THRESH_CA, 0.025)
57  cli.set_config_param(tcc.DAMP_CA, 0.000001)
58 
59  cli.set_config_param(tcc.CONSTR_JLA, tcc.TwistController_JLA)
60  cli.set_config_param(tcc.K_H_JLA, -1.0)
61  cli.set_config_param(tcc.ACTIV_THRESH_JLA, 10.0)
62  cli.set_config_param(tcc.ACTIV_BUF_JLA, 300.0)
63  cli.set_config_param(tcc.CRIT_THRESH_JLA, 5.0)
64  cli.set_config_param(tcc.DAMP_JLA, 0.00001)
65 
66  cli.set_config_param(tcc.KIN_EXT, tcc.TwistController_BASE_ACTIVE)
67  cli.set_config_param(tcc.EXT_RATIO, 0.05)
68  cli.set_config_param(tcc.KEEP_DIR, True)
69  cli.set_config_param(tcc.ENF_VEL_LIM, True)
70  cli.set_config_param(tcc.ENF_POS_LIM, False) # To show that joint pos limits are violated if possible.
71 
72  cli.update()
73  cli.close()
74 
75  cli = Client('frame_tracker')
76  ft_param = {'cart_min_dist_threshold_lin' : 5.0, 'cart_min_dist_threshold_rot' : 5.0}
77  cli.update_configuration(ft_param)
78  cli.close()
79 
80 
81 def init_pos():
82  # Trick to move base back to odom_combined
83  switch_controller = rospy.ServiceProxy('/base/controller_manager/switch_controller', SwitchController)
84  print(switch_controller(None, ['odometry_controller', ], 1)) # switch off
85  time.sleep(1.0)
86  print(switch_controller(['odometry_controller', ], None, 1)) # switch on
87  time.sleep(1.0)
88 
89  sss = simple_script_server()
90  sss.move("arm_left", "side") # for better pics
91  sss.move("arm_right", [[0.6849513492283021, 0.9811503738420306, -0.05053975117653131, -1.4680375957626568, -0.0824580145043452, 0.4964406318714998, -0.5817382519875354]])
92 
93 
94 if __name__ == "__main__":
95  rospy.init_node("test_careobot_st_jla_ca_torus")
96 
97  base_dir = '/home/fxm-mb/bag-files/base_active_arm_right/'
98  if rospy.has_param('~base_dir'):
99  base_dir = rospy.get_param('~base_dir')
100  else:
101  rospy.logwarn('Could not find parameter ~base_dir. Using default base_dir: ' + base_dir)
102 
103  if rospy.has_param('chain_tip_link'):
104  chain_tip_link = rospy.get_param('chain_tip_link')
105  else:
106  rospy.logwarn('Could not find parameter chain_tip_link.')
107  exit(-1)
108 
109  if rospy.has_param('frame_tracker/tracking_frame'):
110  tracking_frame = rospy.get_param('frame_tracker/tracking_frame')
111  else:
112  rospy.logwarn('Could not find parameter frame_tracker/tracking_frame.')
113  exit(-2)
114 
115  if rospy.has_param('root_frame'):
116  root_frame = rospy.get_param('root_frame')
117  else:
118  rospy.logwarn('Could not find parameter root_frame.')
119  exit(-3)
120 
121  t = time.localtime()
122  launch_time_stamp = time.strftime("%Y%m%d_%H_%M_%S", t)
123  command = 'rosbag play ' + base_dir + 'base_active_arm_right.bag'
124 
125  data_krakens = [
126  JointStateDataKraken(base_dir + 'careobot_base_joint_state_data_' + launch_time_stamp + '.csv'),
127  ObstacleDistanceDataKraken(base_dir + 'careobot_base_obst_dist_data_' + launch_time_stamp + '.csv'),
128  TwistDataKraken(base_dir + 'careobot_base_twist_data_' + launch_time_stamp + '.csv', True, False),
129  TwistDataKraken(base_dir + 'careobot_base_twist_controller_commanded_twist_data_' + launch_time_stamp + '.csv', False, False),
130  JointVelocityDataKraken(base_dir + 'careobot_base_joint_vel_data_' + launch_time_stamp + '.csv'),
131  OdometryDataKraken(base_dir + 'careobot_base_odometry_data_' + launch_time_stamp + '.csv'),
132  ]
133 
134  init_pos()
136 
137 
138  exit()
139 
140 
141  status_open = True
142  for data_kraken in data_krakens:
143  status_open = status_open and data_kraken.open()
144  if status_open:
145  rospy.loginfo('Subscribers started for data collection ... \nPress CTRL+C to stop program and write data to the file.')
146 
147  pid = subprocess.Popen(command, stdin = subprocess.PIPE, cwd = base_dir, shell = True)
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  else:
176  rospy.logerr('Failed to open DataKraken files.')
177 
178 
179 
180 
181 
182 
183 


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