20 from ros_ethercat_model.calibrate_class 
import Calibrate
    21 from sr_utilities.hand_finder 
import HandFinder
    29         hand_finder = HandFinder()
    30         joints = hand_finder.get_hand_joints()
    31         mapping = hand_finder.get_hand_parameters().mapping
    33             prefix = mapping[hand]
    34             for joint 
in joints[prefix]:
    35                 if joint[3:5].lower() == 
'th' or joint[3:5].lower() == 
'wr' or (joint[6] != 
'1' and joint[6] != 
'2'):
    36                     joint_controller = 
'cal_sh_' + joint.lower()
    38                     joint = joint[:6] + 
'0'    39                     joint_controller = 
'cal_sh_' + joint.lower()
    40                 if joint_controller 
not in controllers:
    41                     controllers.append(joint_controller)
    46     if rospy.is_shutdown():
    49     rospy.init_node(
'calibration', anonymous=
True)
    52     controllers = calibrate_class.generate_controllers()
    54     calibrate_class.pub_calibrated.publish(
False)
    56     cal_imu = rospy.get_param(
'calibrate_imu', 
False)
    59         imustatus = calibrate_class.calibrate_imu()
    63     if not calibrate_class.calibrate(controllers):
    66     calibrate_class.pub_calibrated.publish(
True)
    69         print(
"Mechanism calibration complete, but IMU calibration failed")
    71         print(
"Calibration complete")
    75 if __name__ == 
'__main__':
 
def generate_controllers()