00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 import rospy
00037
00038 from sensor_msgs.msg import JointState
00039 from sensor_msgs.msg import Imu
00040 from nav_msgs.msg import Odometry
00041
00042 from nao_driver import NaoNode
00043
00044 from tf import transformations
00045 import tf
00046
00047
00048 import motion
00049
00050 class NaoSensors(NaoNode):
00051 def __init__(self):
00052 NaoNode.__init__(self, 'nao_sensors')
00053
00054 self.connectNaoQi()
00055
00056
00057 self.sensorRate = rospy.Rate(rospy.get_param('~sensor_rate', 25.0))
00058
00059 self.dataNamesList = ["DCM/Time",
00060 "Device/SubDeviceList/InertialSensor/AngleX/Sensor/Value","Device/SubDeviceList/InertialSensor/AngleY/Sensor/Value",
00061 "Device/SubDeviceList/InertialSensor/AngleZ/Sensor/Value",
00062 "Device/SubDeviceList/InertialSensor/GyroscopeX/Sensor/Value", "Device/SubDeviceList/InertialSensor/GyroscopeY/Sensor/Value",
00063 "Device/SubDeviceList/InertialSensor/GyroscopeZ/Sensor/Value",
00064 "Device/SubDeviceList/InertialSensor/AccelerometerX/Sensor/Value", "Device/SubDeviceList/InertialSensor/AccelerometerY/Sensor/Value",
00065 "Device/SubDeviceList/InertialSensor/AccelerometerZ/Sensor/Value"]
00066
00067
00068 tf_prefix_param_name = rospy.search_param('tf_prefix')
00069 if tf_prefix_param_name:
00070 self.tf_prefix = rospy.get_param(tf_prefix_param_name)
00071 else:
00072 self.tf_prefix = ""
00073
00074 self.base_frameID = rospy.get_param('~base_frame_id', "base_link")
00075 if not(self.base_frameID[0] == '/'):
00076 self.base_frameID = self.tf_prefix + '/' + self.base_frameID
00077
00078
00079 self.useJointSensors = rospy.get_param('~use_joint_sensors', True)
00080
00081 self.torsoOdom = Odometry()
00082 self.torsoOdom.header.frame_id = rospy.get_param('~odom_frame_id', "odom")
00083 if not(self.torsoOdom.header.frame_id[0] == '/'):
00084 self.torsoOdom.header.frame_id = self.tf_prefix + '/' + self.torsoOdom.header.frame_id
00085
00086 self.torsoIMU = Imu()
00087 self.torsoIMU.header.frame_id = self.base_frameID
00088 self.jointState = JointState()
00089 self.jointState.name = self.motionProxy.getJointNames('Body')
00090
00091
00092 if (len(self.jointState.name) == 22):
00093 self.jointState.name.insert(6,"LWristYaw")
00094 self.jointState.name.insert(7,"LHand")
00095 self.jointState.name.append("RWristYaw")
00096 self.jointState.name.append("RHand")
00097
00098 msg = "Nao joints found: "+ str(self.jointState.name)
00099 rospy.logdebug(msg)
00100
00101 self.torsoOdomPub = rospy.Publisher("odom", Odometry, queue_size=10)
00102 self.torsoIMUPub = rospy.Publisher("imu", Imu, queue_size=10)
00103 self.jointStatePub = rospy.Publisher("joint_states", JointState, queue_size=10)
00104
00105 self.tf_br = tf.TransformBroadcaster()
00106
00107 rospy.loginfo("nao_sensors initialized")
00108
00109
00110 def connectNaoQi(self):
00111 rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
00112 self.motionProxy = self.get_proxy("ALMotion")
00113 self.memProxy = self.get_proxy("ALMemory")
00114 if self.motionProxy is None or self.memProxy is None:
00115 exit(1)
00116
00117 def run(self):
00118 """ Odometry thread code - collects and sends out odometry esimate. """
00119 while self.is_looping():
00120
00121
00122
00123 timestamp = rospy.Time.now()
00124 try:
00125 memData = self.memProxy.getListData(self.dataNamesList)
00126
00127 odomData = self.motionProxy.getPosition('Torso', motion.SPACE_WORLD, True)
00128 positionData = self.motionProxy.getAngles('Body', self.useJointSensors)
00129 except RuntimeError, e:
00130 print "Error accessing ALMemory, exiting...\n"
00131 print e
00132 rospy.signal_shutdown("No NaoQI available anymore")
00133
00134 self.torsoOdom.header.stamp = timestamp
00135 if len(odomData)==2:
00136 odomData = odomData[1]
00137 elif len(odomData)!=6:
00138 print "Error getting odom data"
00139 continue
00140
00141 self.torsoOdom.pose.pose.position.x = odomData[0]
00142 self.torsoOdom.pose.pose.position.y = odomData[1]
00143 self.torsoOdom.pose.pose.position.z = odomData[2]
00144 q = transformations.quaternion_from_euler(odomData[3], odomData[4], odomData[5])
00145 self.torsoOdom.pose.pose.orientation.x = q[0]
00146 self.torsoOdom.pose.pose.orientation.y = q[1]
00147 self.torsoOdom.pose.pose.orientation.z = q[2]
00148 self.torsoOdom.pose.pose.orientation.w = q[3]
00149
00150 t = self.torsoOdom.pose.pose.position
00151 q = self.torsoOdom.pose.pose.orientation
00152 self.tf_br.sendTransform((t.x, t.y, t.z), (q.x, q.y, q.z, q.w),
00153 timestamp, self.base_frameID, self.torsoOdom.header.frame_id)
00154
00155 self.torsoOdomPub.publish(self.torsoOdom)
00156
00157
00158
00159
00160 for i, m in enumerate(memData):
00161 if m is None:
00162 memData[i] = 0
00163
00164 if len(memData) != len(self.dataNamesList):
00165 print "memData length does not match expected length"
00166 print memData
00167 continue
00168
00169
00170
00171 self.torsoIMU.header.stamp = timestamp
00172 q = transformations.quaternion_from_euler(memData[1], memData[2], memData[3])
00173 self.torsoIMU.orientation.x = q[0]
00174 self.torsoIMU.orientation.y = q[1]
00175 self.torsoIMU.orientation.z = q[2]
00176 self.torsoIMU.orientation.w = q[3]
00177
00178 self.torsoIMU.angular_velocity.x = memData[4]
00179 self.torsoIMU.angular_velocity.y = memData[5]
00180 self.torsoIMU.angular_velocity.z = memData[6]
00181
00182 self.torsoIMU.linear_acceleration.x = memData[7]
00183 self.torsoIMU.linear_acceleration.y = memData[8]
00184 self.torsoIMU.linear_acceleration.z = memData[9]
00185
00186
00187
00188 self.torsoIMU.orientation_covariance[0] = -1
00189 self.torsoIMU.angular_velocity_covariance[0] = -1
00190 self.torsoIMU.linear_acceleration_covariance[0] = -1
00191
00192 self.torsoIMUPub.publish(self.torsoIMU)
00193
00194
00195 self.jointState.header.stamp = timestamp
00196 self.jointState.header.frame_id = self.base_frameID
00197 self.jointState.position = positionData
00198
00199
00200 if (len(self.jointState.position) == 22):
00201 self.jointState.position.insert(6, 0.0)
00202 self.jointState.position.insert(7, 0.0)
00203 self.jointState.position.append(0.0)
00204 self.jointState.position.append(0.0)
00205
00206 self.jointStatePub.publish(self.jointState)
00207
00208 self.sensorRate.sleep()
00209
00210 if __name__ == '__main__':
00211
00212 sensors = NaoSensors()
00213 sensors.start()
00214
00215 rospy.spin()
00216 exit(0)