Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007 #include "ros/ros.h"
00008 #include "neuro_recv/dish_state.h"
00009 #include <cstdlib>
00010 #include <cstdio>
00011 #include <ctime>
00012 #include <cmath>
00013
00014 #define LIMIT 0.003
00015
00021 int main(int argc, char** argv)
00022 {
00023 ros::init(argc, argv, "dish_generator");
00024 ros::NodeHandle n;
00025 ros::Publisher dish_state_pub = n.advertise<neuro_recv::dish_state>
00026 ("dish_states", 1000);
00027 ros::Rate loop_rate(1000);
00028
00029 neuro_recv::dish_state dish;
00030 srand(time(NULL));
00031
00032 ROS_INFO("Dish generator running...");
00033 while (ros::ok())
00034 {
00035 for (int i = 0; i < 60; i++)
00036 {
00037 double offset = (static_cast<double>(rand() % 600) - 300.0) / 1000000.0;
00038 if (abs(dish.samples[i] + offset) > LIMIT)
00039 offset = -offset;
00040 dish.samples[i] += offset;
00041 }
00042 dish_state_pub.publish(dish);
00043 loop_rate.sleep();
00044 }
00045
00046 return 0;
00047 }