< >
Home » Turbot与Python教程 » Turbot与python编程-实现定点拍照

Turbot与python编程-实现定点拍照

Turbot与python教程-实现定点拍照

说明:

  • 介绍如何实现通过python控制turbot实现定点拍照

代码:

  • 参考代码:github
  • 实现代码:
# Script for simulation
# Launch gazebo world prior to run this script

from __future__ import print_function
import sys
import rospy
import cv2
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError

class TakePhoto:
    def __init__(self):

        self.bridge = CvBridge()
        self.image_received = False

        # Connect image topic
        img_topic = "/camera/rgb/image_raw"
        self.image_sub = rospy.Subscriber(img_topic, Image, self.callback)

        # Allow up to one second to connection
        rospy.sleep(1)

    def callback(self, data):

        # Convert image to OpenCV format
        try:
            cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
        except CvBridgeError as e:
            print(e)

        self.image_received = True
        self.image = cv_image

    def take_picture(self, img_title):
        if self.image_received:
            # Save an image
            cv2.imwrite(img_title, self.image)
            return True
        else:
            return False

if __name__ == '__main__':

    # Initialize
    rospy.init_node('take_photo', anonymous=False)
    camera = TakePhoto()

    # Take a photo

    # Use '_image_title' parameter from command line
    # Default value is 'photo.jpg'
    img_title = rospy.get_param('~image_title', 'photo.jpg')

    if camera.take_picture(img_title):
        rospy.loginfo("Saved image " + img_title)
    else:
        rospy.loginfo("No images received")

    # Sleep to give the last log messages time to be sent
    rospy.sleep(1)

演示:

  • 主机,新终端,启动底盘
$ roslaunch turbot_bringup minimal.launch
  • 主机,新终端,启动摄像头
$ roslaunch turbot_bringup kinect.launch
  • 从机,新终端,启动脚本
$ rosrun turbot_code takePhoto.py
  • 图片保存执行命令的当前目录下

参考:

  • http://www.ncnynl.com/archives/201609/821.html

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: turbot与python编程