my_publisher.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <opencv2/highgui/highgui.hpp>
4 #include <cv_bridge/cv_bridge.h>
5 
6 int main(int argc, char** argv)
7 {
8  ros::init(argc, argv, "image_publisher");
11  image_transport::Publisher pub = it.advertise("camera/image", 1);
12 
13  cv::Mat image = cv::imread(argv[1], CV_LOAD_IMAGE_COLOR);
14  sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
15 
16  ros::Rate loop_rate(5);
17  while (nh.ok()) {
18  pub.publish(msg);
19  ros::spinOnce();
20  loop_rate.sleep();
21  }
22 }
23 
Manages advertisements of multiple transport options on an Image topic.
Definition: publisher.h:64
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
int main(int argc, char **argv)
Definition: my_publisher.cpp:6
void publish(const sensor_msgs::Image &message) const
Publish an image on the topics associated with this Publisher.
Definition: publisher.cpp:156
bool sleep()
Advertise and subscribe to image topics.
bool ok() const
ROSCPP_DECL void spinOnce()


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Apr 4 2020 03:14:58