ROS机器人Diego 1# 利用人工智能 风格迁移技术拍摄不同画风的视频
风格迁移,就是将一种图片的风格迁移到其他图片上,改变其他图片的风格,很好玩的一个人工自能模型,github上已经有很多实现的方法,本文参考https://github.com/hzy46/fast-neural-style-tensorflow 的算法,利用Diego1#的平台实现实时视频的风格转换,先上两张图看效果:是不是很酷呢,其实实现方法和上篇博文中的原理是一样的,只是把人工智能的
更多创客作品,请关注笔者网站园丁鸟,搜集全球极具创意,且有价值的创客作品
风格迁移,就是将一种图片的风格迁移到其他图片上,改变其他图片的风格,很好玩的一个人工自能模型,github上已经有很多实现的方法,本文参考https://github.com/hzy46/fast-neural-style-tensorflow 的算法,利用Diego1#的平台实现实时视频的风格转换,先上两张图看效果:
[外链图片转存失败,源站可能有防盗链机制,建议将图片保存下来直接上传(img-Ai79SA1v-1588137604563)(https://img-blog.csdn.net/20170728202452506?watermark/2/text/aHR0cDovL2Jsb2cuY3Nkbi5uZXQvbXdsd2xt/font/5a6L5L2T/fontsize/400/fill/I0JBQkFCMA==/dissolve/70/gravity/SouthEast)]
是不是很酷呢,其实实现方法和上篇博文中的原理是一样的,只是把人工智能的算法包装成一个ROS Node,把结果发布为Compressed Image,所以这里只把node节点的代码贴出来,原理就不在讲解了,模型的源代码可以到上面提到的github上去下载
这里写代码片#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Image as ROSImage
from sensor_msgs.msg import CompressedImage as ROSImage_C
from cv_bridge import CvBridge
import numpy as np
import os
import tensorflow as tf
import PIL.Image as Image
import time
import StringIO
from fast_neural_style.preprocessing import preprocessing_factory
from fast_neural_style import reader
from fast_neural_style import model
class fastNeuralStyle():
def __init__(self):
rospy.init_node('fastNeuralStyle')
# Set the shutdown function (stop the robot)
rospy.on_shutdown(self.shutdown)
image_topic = rospy.get_param("~image_topic", "")
self.model_file=rospy.get_param("~model_file", "")
self.loss_model=rospy.get_param("~loss_model", "")
self._cv_bridge = CvBridge()
self.vfc=0
self._sub = rospy.Subscriber(image_topic, ROSImage, self.callback, queue_size=1)
self._pub = rospy.Publisher('fast_Neural_Style', ROSImage_C, queue_size=1)
rospy.loginfo("initialization has finished...")
def callback(self,image_msg):
if self.vfc<12:
self.vfc=self.vfc+1
else:
self.callbackfun(image_msg)
self.vfc=0
def callbackfun(self, image_msg):
with tf.Graph().as_default():
with tf.Session().as_default() as sess:
cv_image = self._cv_bridge.imgmsg_to_cv2(image_msg, "bgr8")
pil_img = Image.fromarray(cv_image)
(im_width, im_height) = pil_img.size
# Read image data.
image_preprocessing_fn, _ = preprocessing_factory.get_preprocessing(
self.loss_model,
is_training=False)
image_np =np.array(pil_img.getdata()).reshape((im_height, im_width, 3)).astype(np.uint8)
image_np=image_preprocessing_fn(image_np,im_height,im_width)
# Add batch dimension
image_np = tf.expand_dims(image_np, 0)
generated = model.net(image_np, training=False)
generated = tf.cast(generated, tf.uint8)
# Remove batch dimension
generated = tf.squeeze(generated, [0])
# Restore model variables.
saver = tf.train.Saver(tf.global_variables(), write_version=tf.train.SaverDef.V1)
sess.run([tf.global_variables_initializer(), tf.local_variables_initializer()])
# Use absolute path
self.model_file = os.path.abspath(self.model_file)
saver.restore(sess, self.model_file)
jpeg_bin = sess.run(tf.image.encode_jpeg(generated))
jpeg_str = StringIO.StringIO(jpeg_bin)
jpeg_image = Image.open(jpeg_str)
img = np.array(jpeg_image, dtype=np.uint8)
ros_compressed_image=self._cv_bridge.cv2_to_compressed_imgmsg(img)
self._pub.publish(ros_compressed_image)
def shutdown(self):
rospy.loginfo("Stopping the fastNeuralStyle...")
rospy.sleep(1)
if __name__ == '__main__':
try:
fastNeuralStyle()
rospy.spin()
except rospy.ROSInterruptException:
rospy.loginfo("Ros TensorFlow fastNeuralStyle has started.")
开放原子开发者工作坊旨在鼓励更多人参与开源活动,与志同道合的开发者们相互交流开发经验、分享开发心得、获取前沿技术趋势。工作坊有多种形式的开发者活动,如meetup、训练营等,主打技术交流,干货满满,真诚地邀请各位开发者共同参与!
更多推荐
所有评论(0)