modeFactory.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <modeFactory.h>
19 #include <staticMode.h>
20 #include <flashMode.h>
21 #include <breathMode.h>
22 #include <breathColorMode.h>
23 #include <fadeColorMode.h>
24 #include <sequenceMode.h>
25 #include <circleColorMode.h>
26 #include <sweepColorMode.h>
27 #include <distApproxMode.h>
28 #include <glowColorMode.h>
29 #include <xmasMode.h>
30 
32 {
33 }
35 {
36 }
37 
38 boost::shared_ptr<Mode> ModeFactory::create(cob_light::LightMode requestMode, IColorO* colorO)
39 {
42  color.r = requestMode.colors[0].r;
43  color.g = requestMode.colors[0].g;
44  color.b = requestMode.colors[0].b;
45  color.a = requestMode.colors[0].a;
46 
47  switch(requestMode.mode)
48  {
49  case cob_light::LightModes::STATIC:
50  mode.reset(new StaticMode(color, requestMode.priority, requestMode.frequency,\
51  requestMode.pulses, requestMode.timeout));
52  break;
53 
54  case cob_light::LightModes::FLASH:
55  mode.reset(new FlashMode(color, requestMode.priority, requestMode.frequency,\
56  requestMode.pulses, requestMode.timeout));
57  break;
58 
59  case cob_light::LightModes::BREATH:
60  mode.reset(new BreathMode(color, requestMode.priority, requestMode.frequency,\
61  requestMode.pulses, requestMode.timeout));
62  break;
63 
64  case cob_light::LightModes::BREATH_COLOR:
65  mode.reset(new BreathColorMode(color, requestMode.priority, requestMode.frequency,\
66  requestMode.pulses, requestMode.timeout));
67  break;
68 
69  case cob_light::LightModes::FADE_COLOR:
70  mode.reset(new FadeColorMode(color, requestMode.priority, requestMode.frequency,\
71  requestMode.pulses, requestMode.timeout));
72  break;
73 
74  case cob_light::LightModes::SEQ:
75  {
76  std::vector<seq_t> seqs;
77  for(size_t i = 0; i < requestMode.sequences.size(); i++)
78  {
79  seq_t seq;
80  seq.color.r = requestMode.sequences[i].color.r;
81  seq.color.g = requestMode.sequences[i].color.g;
82  seq.color.b = requestMode.sequences[i].color.b;
83  seq.color.a = requestMode.sequences[i].color.a;
84  seq.holdtime = requestMode.sequences[i].hold_time;
85  seq.crosstime = requestMode.sequences[i].cross_time;
86  seqs.push_back(seq);
87  std::cout<<"got new seq: "<<seq.color.r<<" "<<seq.color.g<<" "<<seq.color.b<<std::endl;
88  }
89  mode.reset(new SequenceMode(seqs, requestMode.priority, requestMode.frequency,\
90  requestMode.pulses, requestMode.timeout));
91  }
92  break;
93 
94  case cob_light::LightModes::CIRCLE_COLORS:
95  {
96  std::vector<color::rgba> colors;
97  if(requestMode.colors.empty())
98  {
99  colors.push_back(color);
100  }
101  else
102  {
103  for(size_t i = 0; i < requestMode.colors.size(); i++)
104  {
105  color.r = requestMode.colors[i].r;
106  color.g = requestMode.colors[i].g;
107  color.b = requestMode.colors[i].b;
108  color.a = requestMode.colors[i].a;
109  colors.push_back(color);
110  }
111  }
112  mode.reset(new CircleColorMode(colors, colorO->getNumLeds(), requestMode.priority, requestMode.frequency,\
113  requestMode.pulses, requestMode.timeout));
114  }
115  break;
116 
117  case cob_light::LightModes::SWEEP:
118  {
119  std::vector<color::rgba> colors;
120  if(requestMode.colors.empty())
121  {
122  colors.push_back(color);
123  }
124  else
125  {
126  for(size_t i = 0; i < requestMode.colors.size(); i++)
127  {
128  color.r = requestMode.colors[i].r;
129  color.g = requestMode.colors[i].g;
130  color.b = requestMode.colors[i].b;
131  color.a = requestMode.colors[i].a;
132  colors.push_back(color);
133  }
134  }
135  mode.reset(new SweepColorMode(colors, colorO->getNumLeds(), requestMode.priority, requestMode.frequency,
136  requestMode.pulses, requestMode.timeout));
137  }
138  break;
139 
140  case cob_light::LightModes::DIST_APPROX:
141  mode.reset(new DistApproxMode(colorO->getNumLeds(), requestMode.priority, requestMode.frequency,
142  requestMode.pulses, requestMode.timeout));
143  break;
144 
145  case cob_light::LightModes::GLOW:
146  mode.reset(new GlowColorMode(color, requestMode.priority, requestMode.frequency,\
147  requestMode.pulses, requestMode.timeout));
148  break;
149 
150  case cob_light::LightModes::XMAS:
151  mode.reset(new XMasMode(colorO->getNumLeds(), requestMode.priority, requestMode.frequency,\
152  requestMode.pulses, requestMode.timeout));
153  break;
154 
155  default:
156  mode.reset();
157  }
158 
159  return mode;
160 }
161 
163 {
165 
166  if(requestMode == "Static" || requestMode == "static" || requestMode == "STATIC")
167  {
168  mode.reset(new StaticMode(color));
169  }
170  else if(requestMode == "Flash" || requestMode == "flash" || requestMode == "FLASH")
171  {
172  mode.reset(new FlashMode(color));
173  }
174  else if(requestMode == "Breath" || requestMode == "breath" || requestMode == "BREATH")
175  {
176  mode.reset(new BreathMode(color));
177  }
178  else if(requestMode == "BreathColor" || requestMode == "BreathColor" || requestMode == "BreathColor" ||
179  requestMode == "Breath_Color" || requestMode == "breath_color" || requestMode == "BREATH_COLOR")
180  {
181  mode.reset(new BreathColorMode(color));
182  }
183  else if(requestMode == "FadeColor" || requestMode == "fadecolor" || requestMode == "FADECOLOR" ||
184  requestMode == "Fade_Color" || requestMode == "fade_color" || requestMode == "FADE_COLOR")
185  {
186  mode.reset(new FadeColorMode(color));
187  }
188  else
189  mode.reset();
190 
191  return mode;
192 }
193 
195 {
196  int ret;
197  if (mode == NULL)
198  ret = cob_light::LightModes::NONE;
199  else if(dynamic_cast<StaticMode*>(mode) != NULL)
200  ret = cob_light::LightModes::STATIC;
201  else if(dynamic_cast<FlashMode*>(mode) != NULL)
202  ret = cob_light::LightModes::FLASH;
203  else if(dynamic_cast<BreathMode*>(mode) != NULL)
204  ret = cob_light::LightModes::BREATH;
205  else if(dynamic_cast<BreathColorMode*>(mode) != NULL)
206  ret = cob_light::LightModes::BREATH_COLOR;
207  else if(dynamic_cast<FadeColorMode*>(mode) != NULL)
208  ret = cob_light::LightModes::FADE_COLOR;
209  else if(dynamic_cast<SequenceMode*>(mode) != NULL)
210  ret = cob_light::LightModes::SEQ;
211  else if(dynamic_cast<CircleColorMode*>(mode) != NULL)
212  ret = cob_light::LightModes::CIRCLE_COLORS;
213  else if(dynamic_cast<SweepColorMode*>(mode) != NULL)
214  ret = cob_light::LightModes::SWEEP;
215  else if(dynamic_cast<DistApproxMode*>(mode) != NULL)
216  ret = cob_light::LightModes::DIST_APPROX;
217  else if(dynamic_cast<GlowColorMode*>(mode) != NULL)
218  ret = cob_light::LightModes::GLOW;
219  else if(dynamic_cast<XMasMode*>(mode) != NULL)
220  ret = cob_light::LightModes::XMAS;
221  else
222  ret = cob_light::LightModes::NONE;
223 
224  return ret;
225 }
int getNumLeds()
Definition: iColorO.h:36
Definition: mode.h:26
color::rgba color
Definition: sequenceMode.h:25
double crosstime
Definition: sequenceMode.h:27
static int type(Mode *mode)
static boost::shared_ptr< Mode > create(cob_light::LightMode requestMode, IColorO *colorO)
Definition: modeFactory.cpp:38
double holdtime
Definition: sequenceMode.h:26


cob_light
Author(s): Benjamin Maidel
autogenerated on Wed Apr 7 2021 02:11:39