ROS机器人Diego 1#整合Tensorflow MNIST,玩数字识别
机器学习中最经典的例子就是MNIST通过图片来识别0~9的数字,这篇文章将介绍如何将基于Tensorflow MNIST整合到Diego1#机器人中作为一个节点,此节点将订阅Image消息,通过MNIST识别后将结果发布消息给讯飞语音节点,讯飞语音节点会告诉我们识别的数字是几。
相关源代码已经上传到本人的github。
1. 安装Tensorflow
只需一句命令即可安装
pip install tensorflow
官方有4中安装方法,在这里选择直接安装的方式
2. 创建diego_tensorflow_mnist 包
catkin_create_pkg diego_tensorflow_mnist std_msgs rospy roscpp cv_bridge
在diego_tensorflow_mnist目录下创建scripts和launch目录
scripts目录用于存放python的源代码
launch目录用于存放ROS launch文件
下载相关代码到scripts目录
3.ROS节点
有关nnist的算法都已经写好,我们只需要调用其中的功能封装成ROS节点即可,有关封装的代码请见tensorflow_in_ros_mnist.py
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Image
from std_msgs.msg import Int16
from std_msgs.msg import String
from cv_bridge import CvBridge
import cv2
import numpy as np
import tensorflow as tf
def weight_variable(shape):
initial = tf.truncated_normal(shape, stddev=0.1)
return tf.Variable(initial)
def bias_variable(shape):
initial = tf.constant(0.1, shape=shape)
return tf.Variable(initial)
def conv2d(x, W):
return tf.nn.conv2d(x, W, strides=[1, 1, 1, 1],
padding='SAME')
def max_pool_2x2(x):
return tf.nn.max_pool(x, ksize=[1, 2, 2, 1],
strides=[1, 2, 2, 1], padding='SAME')
def makeCNN(x,keep_prob):
# --- define CNN model
W_conv1 = weight_variable([5, 5, 1, 32])
b_conv1 = bias_variable([32])
h_conv1 = tf.nn.relu(conv2d(x, W_conv1) + b_conv1)
h_pool1 = max_pool_2x2(h_conv1)
W_conv2 = weight_variable([3, 3, 32, 64])
b_conv2 = bias_variable([64])
h_conv2 = tf.nn.relu(conv2d(h_pool1, W_conv2) + b_conv2)
h_pool2 = max_pool_2x2(h_conv2)
W_fc1 = weight_variable([7 * 7 * 64, 1024])
b_fc1 = bias_variable([1024])
h_pool2_flat = tf.reshape(h_pool2, [-1, 7 * 7 * 64])
h_fc1 = tf.nn.relu(tf.matmul(h_pool2_flat, W_fc1) + b_fc1)
h_fc1_drop = tf.nn.dropout(h_fc1, keep_prob)
W_fc2 = weight_variable([1024, 10])
b_fc2 = bias_variable([10])
y_conv = tf.nn.softmax(tf.matmul(h_fc1_drop, W_fc2) + b_fc2)
return y_conv
class RosTensorFlow():
def __init__(self):
rospy.init_node('rostensorflow')
# Set the shutdown function (stop the robot)
rospy.on_shutdown(self.shutdown)
model_path = rospy.get_param("~model_path", "")
image_topic = rospy.get_param("~image_topic", "")
self._cv_bridge = CvBridge()
self.x = tf.placeholder(tf.float32, [None,28,28,1], name="x")
self.keep_prob = tf.placeholder("float")
self.y_conv = makeCNN(self.x,self.keep_prob)
self._saver = tf.train.Saver()
self._session = tf.InteractiveSession()
init_op = tf.global_variables_initializer()
self._session.run(init_op)
self._saver.restore(self._session, model_path+"/model.ckpt")
self._sub = rospy.Subscriber(image_topic, Image, self.callback, queue_size=1)
#self._pub = rospy.Publisher('result', Int16, queue_size=1)
self._pub = rospy.Publisher('xfwords', String, queue_size=1)
def callback(self, image_msg):
cv_image = self._cv_bridge.imgmsg_to_cv2(image_msg, "bgr8")
cv_image_gray = cv2.cvtColor(cv_image, cv2.COLOR_RGB2GRAY)
ret,cv_image_binary = cv2.threshold(cv_image_gray,128,255,cv2.THRESH_BINARY_INV)
cv_image_28 = cv2.resize(cv_image_binary,(28,28))
np_image = np.reshape(cv_image_28,(1,28,28,1))
predict_num = self._session.run(self.y_conv, feed_dict={self.x:np_image,self.keep_prob:1.0})
answer = np.argmax(predict_num,1)
rospy.loginfo('%d' % answer)
self._pub.publish(str(answer))
rospy.sleep(3)
def shutdown(self):
rospy.loginfo("Stopping the tensorflow nnist...")
rospy.sleep(1)
if __name__ == '__main__':
try:
RosTensorFlow()
rospy.spin()
except rospy.ROSInterruptException:
rospy.loginfo("RosTensorFlow has started.")
有关MNIST具体算法实现部分网上有很多教程,这里只说明与ROS整合部分
class RosTensorFlow():
def __init__(self):
rospy.init_node('rostensorflow')
# Set the shutdown function (stop the robot)
rospy.on_shutdown(self.shutdown)
model_path = rospy.get_param("~model_path", "")
image_topic = rospy.get_param("~image_topic", "")
在RosTensorFlow类的开始部分,是标准的节点定义方法,model_path变量用于获取launch文件中定义的model的路径,image_topic变量用于获取launch文件中定义image主题
self._sub = rospy.Subscriber(image_topic, Image, self.callback, queue_size=1)
以上这段代码是让该节点订阅image topic,并且知道回调函数
self._pub = rospy.Publisher('xfwords', String, queue_size=1)
以上这段代码定义将发布讯飞语音主题,xfwords
def callback(self, image_msg):
cv_image = self._cv_bridge.imgmsg_to_cv2(image_msg, "bgr8")
cv_image_gray = cv2.cvtColor(cv_image, cv2.COLOR_RGB2GRAY)
ret,cv_image_binary = cv2.threshold(cv_image_gray,128,255,cv2.THRESH_BINARY_INV)
cv_image_28 = cv2.resize(cv_image_binary,(28,28))
np_image = np.reshape(cv_image_28,(1,28,28,1))
predict_num = self._session.run(self.y_conv, feed_dict={self.x:np_image,self.keep_prob:1.0})
answer = np.argmax(predict_num,1)
rospy.loginfo('%d' % answer)
self._pub.publish(str(answer))
rospy.sleep(3)
主要的处理都在callback回调函数中,首先将从image主题中经过一系列的处理转换成numpy数组,然后调用tensorflow进行识别,将可能的结果过放在predict_num数组中,取其中最有可能的值,就是结果,将结果作为讯飞语音topic发送出去
4.launch文件
在launch文件夹下创建一个名为nnist.launch的文件,文件内容如下:
<launch>
<node pkg="diego_tensorflow_nnist" name="tensorflow_in_ros_mnist" type="tensorflow_in_ros_mnist.py" output="screen">
<param name="image_topic" value="/usb_cam/image_raw" />
<param name="model_path" value="$(find diego_tensorflow_nnist)/scripts/model" />
</node>
</launch>
相关的主题,和路径可以在这里修改
5.启动节点
roscore
rosrun xfei_asr tts_subscribe_speak
roslaunch usb_cam usb_cam-test.launch
roslaunch diego_tensorflow_nnist nest.launch
这里我们用到了usb_cam,有关此包的使用请见http://wiki.ros.org/usb_cam
启动后我们就可以在纸上面写几个数字,放在摄像头前,diego1#会告诉你数字是多少。