This commit is contained in:
parent
dde2110d14
commit
64a48fe858
|
@ -1,5 +1,8 @@
|
|||
#include <ros/ros.h>
|
||||
#include <sensor_msgs/Image.h>
|
||||
#include <std_msgs/UInt8.h>
|
||||
|
||||
ros::Publisher brightness_pub;
|
||||
|
||||
void imageCallback(const sensor_msgs::ImageConstPtr &image)
|
||||
{
|
||||
|
@ -9,14 +12,31 @@ void imageCallback(const sensor_msgs::ImageConstPtr &image)
|
|||
sum += value;
|
||||
}
|
||||
int avg = sum / image->data.size();
|
||||
ROS_INFO("Brightness: %d", avg);
|
||||
|
||||
std_msgs::UInt8 brightness_value;
|
||||
brightness_value.data = avg;
|
||||
brightness_pub.publish(brightness_value);
|
||||
}
|
||||
|
||||
void timerCallback(const ros::TimerEvent&)
|
||||
{
|
||||
ROS_INFO("Timer activate");
|
||||
|
||||
std_srvs::Empty srv;
|
||||
client.call(srv);
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "my_first_node");
|
||||
ros::NodeHandle n("~");
|
||||
|
||||
double timer_period_s;
|
||||
n.param("timer_period_s", timer_period_s, 5.0);
|
||||
|
||||
ros::Subscriber sub = n.subscribe("/camera/color/image_raw", 10, imageCallback);
|
||||
brightness_pub = n.advertise<std_msgs::UInt8>("brightness", 1);
|
||||
ros::Timer timer = n.createTimer(ros::Duration(timer_period_s), timerCallback);
|
||||
|
||||
ROS_INFO("Node started!");
|
||||
ros::spin();
|
||||
|
|
Loading…
Reference in New Issue