18 #ifndef DISTAPPROXMODE_H
19 #define DISTAPPROXMODE_H
25 #include <std_msgs/ColorRGBA.h>
26 #include <sensor_msgs/LaserScan.h>
27 #include <cob_light/LightMode.h>
29 #include <boost/thread.hpp>
30 #include <boost/algorithm/clamp.hpp>
35 DistApproxMode(
size_t num_leds,
int priority = 0,
double freq = 5,
int pulses = 0,
double timeout = 0)
53 boost::mutex::scoped_lock lock(
mutex);
63 std::vector<float> ranges =
scan.ranges;
65 float sector_size = (float)ranges.size() / (float)
_num_leds;
66 std::vector<float> sectors;
72 float sum = std::numeric_limits<float>::max();
74 for(
int j = i*(
int)sector_size; j < (i+1)*(
int)sector_size; j++)
76 if(ranges.at(j) != 0){
77 sum = std::min(ranges.at(j), sum);
90 mean = sectors.back()+sectors.at(i)/2.0f;
94 mean = (sectors.at(i)+sectors.at(i-1))/2.0
f;
116 std::string
getName(){
return std::string(
"DistApproxMode"); }