This commit is contained in:
yul 2024-02-05 06:07:43 +01:00
parent dde2110d14
commit 64a48fe858
1 changed files with 27 additions and 7 deletions

View File

@ -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,15 +12,32 @@ 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("~");
ros::Subscriber sub = n.subscribe("/camera/color/image_raw", 10, imageCallback);
ros::init(argc, argv, "my_first_node");
ros::NodeHandle n("~");
ROS_INFO("Node started!");
ros::spin();
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();
}