23 from simple_script_server
import simple_script_server
24 import twist_controller_config
as tcc
25 from dynamic_reconfigure.client
import Client
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
35 cli = tcc.TwistControllerReconfigureClient()
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)
44 cli.set_config_param(tcc.PRIO_CA, 50)
45 cli.set_config_param(tcc.PRIO_JLA, 100)
47 cli.set_config_param(tcc.SOLVER, tcc.TwistController_STACK_OF_TASKS)
48 cli.set_config_param(tcc.K_H, 1.0)
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.2)
54 cli.set_config_param(tcc.ACTIV_BUF_CA, 50.0)
55 cli.set_config_param(tcc.CRIT_THRESH_CA, 0.1)
57 cli.set_config_param(tcc.CONSTR_JLA, tcc.TwistController_JLA)
58 cli.set_config_param(tcc.K_H_JLA, -0.5)
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)
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)
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)
81 sss.move(
"arm_left", [[2.274847163975995, -0.08568661652370757, -0.8273207226405264, -1.9404110013940103, 1.306315205401929, 1.5627416614617742, -1.1199725164070955], ])
84 if __name__ ==
"__main__":
85 rospy.init_node(
"test_careobot_st_jla_ca_selfcollision_arm_left")
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')
91 rospy.logwarn(
'Could not find parameter ~base_dir. Using default base_dir: ' + base_dir)
93 if rospy.has_param(
'chain_tip_link'):
94 chain_tip_link = rospy.get_param(
'chain_tip_link')
96 rospy.logwarn(
'Could not find parameter chain_tip_link.')
99 if rospy.has_param(
'frame_tracker/tracking_frame'):
100 tracking_frame = rospy.get_param(
'frame_tracker/tracking_frame')
102 rospy.logwarn(
'Could not find parameter frame_tracker/tracking_frame.')
105 if rospy.has_param(
'root_frame'):
106 root_frame = rospy.get_param(
'root_frame')
108 rospy.logwarn(
'Could not find parameter root_frame.')
112 launch_time_stamp = time.strftime(
"%Y%m%d_%H_%M_%S", t)
113 command =
'rosbag play ' + base_dir +
'arm_left_to_head_direct_JLA.bag' 116 JointStateDataKraken(base_dir +
'careobot_st_jla_sca_joint_state_data_' + launch_time_stamp +
'.csv'),
117 ObstacleDistanceDataKraken(base_dir +
'careobot_st_jla_sca_obst_dist_data_' + launch_time_stamp +
'.csv'),
118 TwistDataKraken(base_dir +
'careobot_st_jla_sca_twist_data_' + launch_time_stamp +
'.csv'),
119 JointVelocityDataKraken(base_dir +
'careobot_st_jla_sca_joint_vel_data_' + launch_time_stamp +
'.csv'),
120 FrameTrackingDataKraken(base_dir +
'careobot_st_jla_sca_frame_tracking_data_' + launch_time_stamp +
'.csv', root_frame, chain_tip_link, tracking_frame), ]
126 for data_kraken
in data_krakens:
127 status_open = status_open
and data_kraken.open()
129 rospy.loginfo(
'Subscribers started for data collection ... \nPress CTRL+C to stop program and write data to the file.')
130 pid = subprocess.Popen(command, stdin = subprocess.PIPE, cwd = base_dir, shell =
True)
132 rate = rospy.Rate(10)
134 while not rospy.is_shutdown():
136 if(pid.poll()
is not None):
137 rospy.loginfo(
'Bag file finished stop script.')
140 except (KeyboardInterrupt, SystemExit)
as e:
141 rospy.loginfo(
'KeyboardInterrupt / SystemExit: ' + str(e))
143 for data_kraken
in data_krakens:
144 data_kraken.writeAllData()
146 rospy.logerr(
'Else exception.')
148 for data_kraken
in data_krakens:
149 data_kraken.writeAllData()
153 pid.send_signal(signal.SIGINT)
154 except Exception
as e:
155 rospy.logerr(
'Failed to stop rosbag play due to exception: ' + str(e))
157 rospy.logerr(
'Failed to open DataKraken files.')