3
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

More than 3 years have passed since last update.

ROS+OpenCV 無地の画像のトピックを出すノード[c++][Python]

Last updated at Posted at 2019-06-10

実行環境

Ubuntu 16.04
ROS kinetic

コード[c++]

(2019/6/10更新)

dummy_image_pub_node.cpp
# include <ros/ros.h>
# include <image_transport/image_transport.h>
# include <opencv2/highgui/highgui.hpp>
# include <cv_bridge/cv_bridge.h>

int main(int argc, char** argv)
{
  ros::init(argc, argv, "image_publisher");
  ros::NodeHandle nh;
  image_transport::ImageTransport it(nh);
  image_transport::Publisher pub = it.advertise("/camera/color/image_raw", 1);
  cv::Mat image(cv::Size(640, 480), CV_8UC3, cv::Scalar(0, 100, 0));

  sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();

  ros::Rate loop_rate(1000);//Hz
  while (nh.ok()) {
    pub.publish(msg);
    ros::spinOnce();
    loop_rate.sleep();
  }
}

実行結果

Screenshot from 2019-06-10 20-57-52.png

コード[Python]

(2020/8/23更新)

dummy_image_pub_node.py
# !/usr/bin/env python
# -*- coding: utf-8 -*-


import rospy
from sensor_msgs.msg import Image 
from cv_bridge import CvBridge
import cv2
import numpy as np



if __name__ == '__main__':
    pub = rospy.Publisher('/camera/color/image_raw', Image, queue_size=10)
    rospy.init_node('image_publisher')
    r = rospy.Rate(10) # 10hz
    
    cols = 640
    rows = 480
    img = np.full((rows, cols, 3), 0, dtype=np.uint8)
    img[0:480, 0:640, 1] = 100

    bridge = CvBridge()
    imgMsg = bridge.cv2_to_imgmsg(img, "bgr8")


    while not rospy.is_shutdown():
        rospy.loginfo(img)

        pub.publish(imgMsg)

        r.sleep()

参考サイト

3
0
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
3
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?