distApproxMode.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #ifndef DISTAPPROXMODE_H
00019 #define DISTAPPROXMODE_H
00020 
00021 #include <mode.h>
00022 #include <algorithm>
00023 #include <limits>
00024 
00025 #include <std_msgs/ColorRGBA.h>
00026 #include <sensor_msgs/LaserScan.h>
00027 #include <cob_light/LightMode.h>
00028 
00029 #include <boost/thread.hpp>
00030 #include <boost/algorithm/clamp.hpp>
00031 
00032 class DistApproxMode : public Mode
00033 {
00034 public:
00035     DistApproxMode(size_t num_leds, int priority = 0, double freq = 5, int pulses = 0, double timeout = 0)
00036         :Mode(priority, freq, pulses, timeout), _timer_inc(0), _num_leds(num_leds)
00037     {
00038         ros::NodeHandle nh;
00039         sub_scan = nh.subscribe("/scan_unified", 1, &DistApproxMode::scan_callback, this);
00040         //use static freq for this mode
00041         _inc = (1. / UPDATE_RATE_HZ) * UPDATE_FREQ;
00042 
00043         _colors.resize(_num_leds);
00044 
00045         c_red.a = 1; c_red.r = 1; c_red.g = 0; c_red.b = 0;
00046         c_green.a = 1; c_green.r = 0; c_green.g = 1; c_green.b = 0;
00047         c_off.a = 0; c_off.r = 0; c_off.g = 0; c_off.b = 0;
00048         c_default.a = 0.1; c_default.r = 0; c_default.g = 1.0; c_default.b = 0;
00049     }
00050 
00051     void scan_callback(const sensor_msgs::LaserScanConstPtr& msg)
00052     {
00053         boost::mutex::scoped_lock lock(mutex);
00054         scan = *msg;
00055     }
00056 
00057     void execute()
00058     {
00059         if(_timer_inc >= 1.0)
00060         {
00061             //rotate scan array
00062             mutex.lock();
00063             std::vector<float> ranges = scan.ranges;
00064             mutex.unlock();
00065             float sector_size = (float)ranges.size() / (float)_num_leds;
00066             std::vector<float> sectors;
00067             sectors.assign(_num_leds, 0.0);
00068 
00069             //calculate sector values
00070             for(int i = 0; i < _num_leds; i++)
00071             {
00072                 float sum = std::numeric_limits<float>::max();
00073                 //float sum = 0;
00074                 for(int j = i*(int)sector_size; j < (i+1)*(int)sector_size; j++)
00075                 {
00076                     if(ranges.at(j) != 0){
00077                         sum = std::min(ranges.at(j), sum);
00078                     }
00079                 }
00080                 sectors.at(i) = sum;
00081             }
00082 
00083             for(int i = 0; i < _num_leds; i++)
00084             {
00085                 color::rgba col;
00086 
00087                 float mean = 0;
00088                 if(i == 0)
00089                 {
00090                     mean = sectors.back()+sectors.at(i)/2.0f;
00091                 }
00092                 else
00093                 {
00094                     mean = (sectors.at(i)+sectors.at(i-1))/2.0f;
00095                 }
00096                 if(mean > DIST_MAX)
00097                 {
00098                     col = c_default;
00099                 }
00100                 else
00101                 {
00102                     float t = (boost::algorithm::clamp(mean, DIST_MIN, DIST_MAX) - DIST_MIN)/(DIST_MAX - DIST_MIN);
00103                     col = color::Color::interpolateColor(c_red, c_green, t);
00104                 }
00105 
00106                 _colors.at(i) = col;
00107             }
00108             _pulsed++;
00109             m_sigColorsReady(_colors);
00110             _timer_inc = 0.0;
00111         }
00112         else
00113             _timer_inc += _inc;
00114     }
00115 
00116     std::string getName(){ return std::string("DistApproxMode"); }
00117 
00118     static const float DIST_MIN = 0.3f;
00119     static const float DIST_MAX = 2.0f;
00120     static const double UPDATE_FREQ = 50.0;
00121 
00122 private:
00123     double _timer_inc;
00124     double _inc;
00125     size_t _num_leds;
00126 
00127     sensor_msgs::LaserScan scan;
00128 
00129     ros::Subscriber sub_scan;
00130     boost::mutex mutex;
00131     color::rgba c_red;
00132     color::rgba c_green;
00133     color::rgba c_off;
00134     color::rgba c_default;
00135 };
00136 
00137 const float DistApproxMode::DIST_MIN;
00138 const float DistApproxMode::DIST_MAX;
00139 const double DistApproxMode::UPDATE_FREQ;
00140 
00141 #endif


cob_light
Author(s): Benjamin Maidel
autogenerated on Sat Jun 8 2019 21:02:07