This commit is contained in:
parent
4b38562914
commit
6a9821bf39
|
@ -1,9 +1,10 @@
|
||||||
#include <ros/ros.h>
|
#include <ros/ros.h>
|
||||||
#include <sensor_msgs/Image.h>
|
#include <sensor_msgs/Image.h>
|
||||||
#include <std_msgs/UInt8.h>
|
#include <std_msgs/UInt8.h>
|
||||||
#include "std_srvs/Empty.h"
|
#include <std_srvs/Empty.h>
|
||||||
|
|
||||||
ros::Publisher brightness_pub;
|
ros::Publisher brightness_pub;
|
||||||
|
ros::ServiceClient client;
|
||||||
|
|
||||||
void imageCallback(const sensor_msgs::ImageConstPtr &image)
|
void imageCallback(const sensor_msgs::ImageConstPtr &image)
|
||||||
{
|
{
|
||||||
|
@ -38,6 +39,7 @@ int main(int argc, char **argv)
|
||||||
ros::Subscriber sub = n.subscribe("/camera/color/image_raw", 10, imageCallback);
|
ros::Subscriber sub = n.subscribe("/camera/color/image_raw", 10, imageCallback);
|
||||||
brightness_pub = n.advertise<std_msgs::UInt8>("brightness", 1);
|
brightness_pub = n.advertise<std_msgs::UInt8>("brightness", 1);
|
||||||
ros::Timer timer = n.createTimer(ros::Duration(timer_period_s), timerCallback);
|
ros::Timer timer = n.createTimer(ros::Duration(timer_period_s), timerCallback);
|
||||||
|
client = n.serviceClient<std_srvs::Empty>("/image_saver/save");
|
||||||
|
|
||||||
ROS_INFO("Node started!");
|
ROS_INFO("Node started!");
|
||||||
ros::spin();
|
ros::spin();
|
||||||
|
|
Loading…
Reference in New Issue