ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

how to publisher image and camera

asked 2014-09-17 11:19:31 -0500

turtle gravatar image

updated 2014-09-17 20:13:00 -0500

I don't know publisher image and camera Can you help me ? I use ros fuerte . I want to publisher camera but i don't now !

edit retag flag offensive close merge delete

Comments

1

Please write more about what your looking for.

bvbdort gravatar image bvbdort  ( 2014-09-17 13:08:14 -0500 )edit

There are many ROS camera driver packages. Use one that supports your device: http://wiki.ros.org/Sensors/Cameras .

joq gravatar image joq  ( 2014-09-18 09:55:13 -0500 )edit

If you tell us what kind of camera you have, someone can probably suggest a good driver.

joq gravatar image joq  ( 2014-09-18 09:56:12 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2014-09-18 05:06:32 -0500

Hamid Didari gravatar image

updated 2014-09-18 05:12:06 -0500

an example of code that get image from camera then publish the image:

#include "camera.h"



CameraDriver::CameraDriver()
{

    ros::NodeHandle n("~");

    n.param( "camera_index", id_camera, -1);
    n.param( "show", show , false );
    n.param( "fps", fps , 30 );

    cvi.header.frame_id = "image";
    cvi.encoding = sensor_msgs::image_encodings::BGR8;



    it = new image_transport::ImageTransport(n);

    pub=it->advertise("/image_raw",1);


    if(id_camera == -1)
    {
          ROS_WARN("camera's id has not recived");
          ROS_WARN("I will open  every camera that I find :P ");
    }

    input_video.open(id_camera);
    input_video.set(CV_CAP_PROP_FPS,fps);

    if(!input_video.isOpened())
    {
        ROS_ERROR("Couldn't Open The Camera !");
        ROS_ERROR("Babay :(");
        ros::shutdown();
    }


    ros::Rate loop_rate(fps);

    while (ros::ok())
    {

        input_video.read(frame);
        cvi.image=frame;
        cvi.header.stamp = ros::Time::now();
        pub.publish(cvi.toImageMsg());

        if(show)
        {
            imshow("imgout.jpg", frame);
            if(waitKey(1) > 0);
        }

        loop_rate.sleep();

    }



}

and .h

#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include "opencv/cv.h"
#include "opencv/highgui.h"
#include "cv_bridge/cv_bridge.h"
#include <sensor_msgs/image_encodings.h>
#include <image_transport/image_transport.h>
#include <sensor_msgs/image_encodings.h>



using namespace std;
using namespace cv;

class CameraDriver
{
public:
    int id_camera;
    int fps;
    bool show;
    VideoCapture input_video;
    Mat frame;
    cv_bridge::CvImage cvi;
    image_transport::ImageTransport *it;
    image_transport::Publisher pub;
    explicit CameraDriver();

};
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-09-17 11:19:31 -0500

Seen: 2,610 times

Last updated: Sep 18 '14