24 import rosgraph.masterapi
25 import control_msgs.msg
26 from sr_robot_msgs.msg
import sendupdate, joint, joints_data, JointControllerState
27 from sensor_msgs.msg
import JointState
28 from std_msgs.msg
import Float64
34 from dynamic_reconfigure.msg
import Config
39 def __init__(self, name="", motor="", j_min=0, j_max=90):
49 This is a python library used to easily access the shadow hand ROS interface. 54 Builds the library, creates the communication node in ROS and 55 initializes the hand publisher and subscriber to the default 56 values of shadowhand_data and sendupdate 59 Joint(
"THJ2",
"smart_motor_th2", -40, 40),
60 Joint(
"THJ3",
"smart_motor_th3", -15, 15),
61 Joint(
"THJ4",
"smart_motor_th4", 0, 75),
62 Joint(
"THJ5",
"smart_motor_th5", -60, 60),
63 Joint(
"FFJ0",
"smart_motor_ff2", 0, 180),
64 Joint(
"FFJ3",
"smart_motor_ff3"),
65 Joint(
"FFJ4",
"smart_motor_ff4", -20, 20),
66 Joint(
"MFJ0",
"smart_motor_mf2", 0, 180),
67 Joint(
"MFJ3",
"smart_motor_mf3"),
68 Joint(
"MFJ4",
"smart_motor_mf4", -20, 20),
69 Joint(
"RFJ0",
"smart_motor_rf2", 0, 180),
70 Joint(
"RFJ3",
"smart_motor_rf3"),
71 Joint(
"RFJ4",
"smart_motor_rf4", -20, 20),
72 Joint(
"LFJ0",
"smart_motor_lf2", 0, 180),
73 Joint(
"LFJ3",
"smart_motor_lf3"),
74 Joint(
"LFJ4",
"smart_motor_lf4", -20, 20),
75 Joint(
"LFJ5",
"smart_motor_lf5", 0, 45),
76 Joint(
"WRJ1",
"smart_motor_wr1", -45, 30),
77 Joint(
"WRJ2",
"smart_motor_wr2", -30, 10),
81 Joint(
"ShoulderJSwing",
"", 0, 80),
82 Joint(
"ElbowJSwing",
"", 0, 120),
83 Joint(
"ElbowJRotate",
"", -80, 80)
119 self.
rootPath = rospkg.RosPack().get_path(
'sr_hand')
120 self.grasp_parser.parse_tree(
121 self.
rootPath +
"/scripts/sr_hand/grasps.xml")
124 self.
pub = rospy.Publisher(
125 'srh/sendupdate', sendupdate, queue_size=1, latch=
True)
127 'sr_arm/sendupdate', sendupdate, queue_size=1, latch=
True)
130 'sr_arm/shadowhand_data', joints_data, self.
callback_arm)
131 self.
sub = rospy.Subscriber(
132 'srh/shadowhand_data', joints_data, self.
callback)
149 topic, Float64, queue_size=1, latch=
True)
152 threading.Thread(
None, rospy.spin)
159 @param data: The ROS message received which called the callback 160 If the message is the first received, initializes the dictionnaries 161 Else, it updates the lastMsg 162 @param joint: a Joint object that contains the name of the joint that we receive data from 164 joint_data = joint(joint_name=jointName, joint_target=math.degrees(
165 float(data.set_point)), joint_position=math.degrees(float(data.process_value)))
174 for joint_name
in self.dict_ethercat_joints.keys():
175 self.lastMsg.joints_list.append(
194 @param data: The ROS message received which called the callback 195 If the message is the first received, initializes the dictionnaries 196 Else, it updates the lastMsg 201 for jnt
in self.lastMsg.joints_list:
202 self.
dict_pos[jnt.joint_name] = jnt.joint_position
203 self.
dict_tar[jnt.joint_name] = jnt.joint_target
209 @param data: The ROS message received which called the callback 210 If the message is the first received, initializes the dictionnaries 211 Else, it updates the lastMsg 215 for jnt
in self.lastArmMsg.joints_list:
221 Initializes the library with just the fingers actually connected 224 for joint_msg
in self.lastMsg.joints_list:
225 if joint_msg.joint_name == joint_all.name:
226 self.handJoints.append(joint_all)
230 @return : true if some hand is detected 242 @return : true if the CAN hand is detected 249 "Waiting for service since " + str(t) +
" seconds...")
252 "No hand found. Are you sure the ROS hand is running ?")
258 @param topic: The new topic to be set as the hand publishing topic 259 Set the library to listen to a new topic 261 print 'Changing subscriber to ' + topic
262 self.
sub = rospy.Subscriber(topic, joints_data, self.
callback)
266 @param topic: The new topic to be set as the hand subscribing topic 267 Set the library to publish to a new topic 269 print 'Changing publisher to ' + topic
270 self.
pub = rospy.Publisher(topic, sendupdate, latch=
True)
274 @param dicti: Dictionnary containing all the targets to send, mapping 275 the name of the joint to the value of its target. 276 Sends new targets to the hand from a dictionnary 278 self.sendupdate_lock.acquire()
281 for join
in dicti.keys():
287 topic, Float64, latch=
True)
289 msg_to_send = Float64()
290 msg_to_send.data = math.radians(float(dicti[join]))
294 for join
in dicti.keys():
296 joint(joint_name=join, joint_target=dicti[join]))
297 self.pub.publish(
sendupdate(len(message), message))
299 self.sendupdate_lock.release()
303 @param jointName: Name of the joint to update 304 @param angle: Target of the joint, 0 if not set 305 Sends a new target for the specified joint 307 self.sendupdate_lock.acquire()
314 topic, Float64, latch=
True)
316 msg_to_send = Float64()
317 msg_to_send.data = math.radians(float(angle))
320 message = [joint(joint_name=jointName, joint_target=angle)]
321 self.pub.publish(
sendupdate(len(message), message))
323 self.sendupdate_lock.release()
327 @param dicti: Dictionnary containing all the targets to send, mapping 328 the name of the joint to the value of its target. 329 Sends new targets to the hand from a dictionnary 332 for join
in dicti.keys():
333 message.append(joint(joint_name=join, joint_target=dicti[join]))
334 self.pub_arm.publish(
sendupdate(len(message), message))
338 @param jointName: Name of the joint to update 339 @param angle: Target of the joint, 0 if not set 340 Sends a new target for the specified joint 342 message = [joint(joint_name=jointName, joint_target=angle)]
343 self.pub_arm.publish(
sendupdate(len(message), message))
347 @param jointName: Name of the joint to read the value 348 @return: 'NaN' if the value is not correct, the actual position of the joint else 350 for jnt
in self.lastMsg.joints_list:
351 if jnt.joint_name == jointName:
352 return float(jnt.joint_position)
353 for jnt
in self.lastArmMsg.joints_list:
354 if jnt.joint_name == jointName:
355 return float(jnt.joint_position)
360 @return : True if an arm is detected on the roscore 366 master = rosgraph.masterapi.Master(
'/rostopic')
367 self.
liste = master.getPublishedTopics(
'/')
368 for topic_typ
in self.
liste:
369 for topic
in topic_typ:
370 if 'sr_arm/shadowhand_data' in topic:
376 @param filename: name (or path) of the file to save to 377 @param grasp_as_xml: xml-formatted grasp 378 Write the grasp at the end of the file, creates the file if does not exist 380 if os.path.exists(filename):
381 obj = open(filename,
'r') 382 text = obj.readlines() 384 objWrite = open(filename, 'w')
385 for index
in range(0, len(text) - 1):
386 objWrite.write(text[index])
387 objWrite.write(grasp_as_xml)
388 objWrite.write(
'</root>')
391 objWrite = open(filename,
'w')
392 objWrite.write(
'<root>\n')
393 objWrite.write(grasp_as_xml)
394 objWrite.write(
'</root>')
398 objFile = open(filename,
'w')
400 objFile.write(key +
' ' + value +
'\n')
405 @return: dictionnary mapping joint names to actual positions 406 Read all the positions in the lastMsg 410 for jnt
in self.lastMsg.joints_list:
411 self.
dict_pos[jnt.joint_name] = jnt.joint_position
416 @return: dictionnary mapping joint names to current targets 417 Read all the targets in the lastMsg 419 for jnt
in self.lastMsg.joints_list:
420 self.
dict_tar[jnt.joint_name] = jnt.joint_target
425 @return: dictionary mapping joint names to current velocities 432 @return: dictionary mapping joint names to current efforts 439 @return: dictionnary mapping joint names to actual positions 440 Read all the positions in the lastMsg 442 for jnt
in self.lastArmMsg.joints_list:
448 @return: dictionnary mapping joint names to actual targets 449 Read all the targets in the lastMsg 451 for jnt
in self.lastArmMsg.joints_list:
457 Resend the targets read in the lastMsg to the hand 459 for key, value
in self.dict_tar.items():
464 @param callList: dictionnary mapping joint names to information that should be displayed 465 @param reset: flag used to tell if the parameters should be replaced by the new ones or 466 just added to the previous ones. 467 Calls a ROS service to display various information in Rviz 477 Only used to check if a real etherCAT hand is detected in the system 478 check if something is being published to this topic, otherwise 480 Bear in mind that the gazebo hand also publishes the joint_states topic, 481 so we need to check for the gazebo hand first 485 rospy.wait_for_message(
"joint_states", JointState, timeout=0.2)
486 except rospy.ROSException:
487 rospy.logwarn(
"no message received from joint_states")
494 Only used to check if a Gazebo simulated (etherCAT protocol) hand is detected in the system 495 check if something is being published to this topic, otherwise 500 rospy.wait_for_message(
501 "gazebo/parameter_updates", Config, timeout=0.2)
502 except rospy.ROSException:
509 At the moment we just try to use the mixed position velocity controllers 518 rospy.wait_for_message(
519 topic, control_msgs.msg.JointControllerState, timeout=0.2)
522 self.
topic_ending =
"_mixed_position_velocity_controller" 525 rospy.wait_for_message(
526 topic, JointControllerState, timeout=0.2)
527 except rospy.ROSException:
531 if self.
topic_ending ==
"_mixed_position_velocity_controller":
537 control_msgs.msg.JointControllerState,
548 The callback function for the topic joint_states. 549 It will store the received joint velocity and effort information in two dictionaries 550 Velocity will be converted to degrees/s. 551 Effort units are kept as they are (currently ADC units, as no calibration is performed on the strain gauges) 553 @param joint_state: the message containing the joints data. 557 for n, v
in zip(joint_state.name, joint_state.velocity)}
559 n: e
for n, e
in zip(joint_state.name, joint_state.effort)}
561 for finger
in [
'FF',
'MF',
'RF',
'LF']:
563 if (finger +
'J1')
in dic
and (finger +
'J2')
in dic:
564 dic[finger +
'J0'] = dic[
565 finger +
'J1'] + dic[finger +
'J2']
566 del dic[finger +
'J1']
567 del dic[finger +
'J2']
570 return self.tactile_receiver.get_tactile_type()
573 return self.tactile_receiver.get_tactile_state()
def sendupdate_arm_from_dict(self, dicti)
def callback_arm(self, data)
def joint_states_callback(self, joint_state)
def __init__(self, name="", motor="", j_min=0, j_max=90)
def sendupdate_arm(self, jointName, angle=0)
def get_tactile_state(self)
def record_step_to_file(self, filename, grasp_as_xml)
def activate_etherCAT_hand(self)
def sendupdate_from_dict(self, dicti)
def read_all_current_arm_positions(self)
def check_hand_type(self)
def valueof(self, jointName)
def get_tactile_type(self)
def save_hand_position_to_file(self, filename)
def init_actual_joints(self)
def callback_ethercat_states(self, data, jointName)
def check_etherCAT_hand_presence(self)
def read_all_current_targets(self)
def read_all_current_velocities(self)
def read_all_current_arm_targets(self)
def create_grasp_interpoler(self, current_step, next_step)
def read_all_current_positions(self)
def read_all_current_efforts(self)
def check_CAN_hand_presence(self)
def callVisualisationService(self, callList=0, reset=0)
def sendupdate(self, jointName, angle=0)
def set_sendupdate_topic(self, topic)
def check_gazebo_hand_presence(self)
def set_shadowhand_data_topic(self, topic)