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 #include <kitMode.h>
31 #include <turnIndicatorMode.h>
32 
34 {
35 }
37 {
38 }
39 
40 boost::shared_ptr<Mode> ModeFactory::create(cob_light::LightMode requestMode, IColorO* colorO)
41 {
44  color.r = requestMode.colors[0].r;
45  color.g = requestMode.colors[0].g;
46  color.b = requestMode.colors[0].b;
47  color.a = requestMode.colors[0].a;
48 
49  switch(requestMode.mode)
50  {
51  case cob_light::LightModes::STATIC:
52  mode.reset(new StaticMode(color, requestMode.priority, requestMode.frequency,\
53  requestMode.pulses, requestMode.timeout));
54  break;
55 
56  case cob_light::LightModes::FLASH:
57  mode.reset(new FlashMode(color, requestMode.priority, requestMode.frequency,\
58  requestMode.pulses, requestMode.timeout));
59  break;
60 
61  case cob_light::LightModes::BREATH:
62  mode.reset(new BreathMode(color, requestMode.priority, requestMode.frequency,\
63  requestMode.pulses, requestMode.timeout));
64  break;
65 
66  case cob_light::LightModes::BREATH_COLOR:
67  mode.reset(new BreathColorMode(color, requestMode.priority, requestMode.frequency,\
68  requestMode.pulses, requestMode.timeout));
69  break;
70 
71  case cob_light::LightModes::FADE_COLOR:
72  mode.reset(new FadeColorMode(color, requestMode.priority, requestMode.frequency,\
73  requestMode.pulses, requestMode.timeout));
74  break;
75 
76  case cob_light::LightModes::SEQ:
77  {
78  std::vector<seq_t> seqs;
79  for(size_t i = 0; i < requestMode.sequences.size(); i++)
80  {
81  seq_t seq;
82  seq.color.r = requestMode.sequences[i].color.r;
83  seq.color.g = requestMode.sequences[i].color.g;
84  seq.color.b = requestMode.sequences[i].color.b;
85  seq.color.a = requestMode.sequences[i].color.a;
86  seq.holdtime = requestMode.sequences[i].hold_time;
87  seq.crosstime = requestMode.sequences[i].cross_time;
88  seqs.push_back(seq);
89  }
90  mode.reset(new SequenceMode(seqs, requestMode.priority, requestMode.frequency,\
91  requestMode.pulses, requestMode.timeout));
92  }
93  break;
94 
95  case cob_light::LightModes::CIRCLE_COLORS:
96  {
97  std::vector<color::rgba> colors;
98  if(requestMode.colors.empty())
99  {
100  colors.push_back(color);
101  }
102  else
103  {
104  for(size_t i = 0; i < requestMode.colors.size(); i++)
105  {
106  color.r = requestMode.colors[i].r;
107  color.g = requestMode.colors[i].g;
108  color.b = requestMode.colors[i].b;
109  color.a = requestMode.colors[i].a;
110  colors.push_back(color);
111  }
112  }
113  mode.reset(new CircleColorMode(colors, colorO->getNumLeds(), requestMode.priority, requestMode.frequency,\
114  requestMode.pulses, requestMode.timeout));
115  }
116  break;
117 
118  case cob_light::LightModes::SWEEP:
119  {
120  std::vector<color::rgba> colors;
121  if(requestMode.colors.empty())
122  {
123  colors.push_back(color);
124  }
125  else
126  {
127  for(size_t i = 0; i < requestMode.colors.size(); i++)
128  {
129  color.r = requestMode.colors[i].r;
130  color.g = requestMode.colors[i].g;
131  color.b = requestMode.colors[i].b;
132  color.a = requestMode.colors[i].a;
133  colors.push_back(color);
134  }
135  }
136  mode.reset(new SweepColorMode(colors, colorO->getNumLeds(), requestMode.priority, requestMode.frequency,
137  requestMode.pulses, requestMode.timeout));
138  }
139  break;
140 
141  case cob_light::LightModes::DIST_APPROX:
142  mode.reset(new DistApproxMode(colorO->getNumLeds(), requestMode.priority, requestMode.frequency,
143  requestMode.pulses, requestMode.timeout));
144  break;
145 
146  case cob_light::LightModes::GLOW:
147  mode.reset(new GlowColorMode(color, requestMode.priority, requestMode.frequency,\
148  requestMode.pulses, requestMode.timeout));
149  break;
150 
151  case cob_light::LightModes::XMAS:
152  mode.reset(new XMasMode(colorO->getNumLeds(), requestMode.priority, requestMode.frequency,\
153  requestMode.pulses, requestMode.timeout));
154  break;
155 
156  case cob_light::LightModes::KIT:
157  mode.reset(new KitMode(color, colorO->getNumLeds(), requestMode.priority, requestMode.frequency,
158  requestMode.pulses, requestMode.timeout));
159  break;
160 
161  case cob_light::LightModes::TURN_LEFT:
162  mode.reset(new TurnIndicatorMode(color, colorO->getNumLeds(), -1, requestMode.priority, requestMode.frequency,
163  requestMode.pulses, requestMode.timeout));
164  break;
165 
166  case cob_light::LightModes::TURN_RIGHT:
167  mode.reset(new TurnIndicatorMode(color, colorO->getNumLeds(), 1, requestMode.priority, requestMode.frequency,
168  requestMode.pulses, requestMode.timeout));
169  break;
170 
171  default:
172  mode.reset();
173  }
174 
175  return mode;
176 }
177 
179 {
181 
182  if(requestMode == "Static" || requestMode == "static" || requestMode == "STATIC")
183  {
184  mode.reset(new StaticMode(color));
185  }
186  else if(requestMode == "Flash" || requestMode == "flash" || requestMode == "FLASH")
187  {
188  mode.reset(new FlashMode(color));
189  }
190  else if(requestMode == "Breath" || requestMode == "breath" || requestMode == "BREATH")
191  {
192  mode.reset(new BreathMode(color));
193  }
194  else if(requestMode == "BreathColor" || requestMode == "BreathColor" || requestMode == "BreathColor" ||
195  requestMode == "Breath_Color" || requestMode == "breath_color" || requestMode == "BREATH_COLOR")
196  {
197  mode.reset(new BreathColorMode(color));
198  }
199  else if(requestMode == "FadeColor" || requestMode == "fadecolor" || requestMode == "FADECOLOR" ||
200  requestMode == "Fade_Color" || requestMode == "fade_color" || requestMode == "FADE_COLOR")
201  {
202  mode.reset(new FadeColorMode(color));
203  }
204  else
205  mode.reset();
206 
207  return mode;
208 }
209 
211 {
212  int ret;
213  if (mode == NULL)
214  ret = cob_light::LightModes::NONE;
215  else if(dynamic_cast<StaticMode*>(mode) != NULL)
216  ret = cob_light::LightModes::STATIC;
217  else if(dynamic_cast<FlashMode*>(mode) != NULL)
218  ret = cob_light::LightModes::FLASH;
219  else if(dynamic_cast<BreathMode*>(mode) != NULL)
220  ret = cob_light::LightModes::BREATH;
221  else if(dynamic_cast<BreathColorMode*>(mode) != NULL)
222  ret = cob_light::LightModes::BREATH_COLOR;
223  else if(dynamic_cast<FadeColorMode*>(mode) != NULL)
224  ret = cob_light::LightModes::FADE_COLOR;
225  else if(dynamic_cast<SequenceMode*>(mode) != NULL)
226  ret = cob_light::LightModes::SEQ;
227  else if(dynamic_cast<CircleColorMode*>(mode) != NULL)
228  ret = cob_light::LightModes::CIRCLE_COLORS;
229  else if(dynamic_cast<SweepColorMode*>(mode) != NULL)
230  ret = cob_light::LightModes::SWEEP;
231  else if(dynamic_cast<DistApproxMode*>(mode) != NULL)
232  ret = cob_light::LightModes::DIST_APPROX;
233  else if(dynamic_cast<GlowColorMode*>(mode) != NULL)
234  ret = cob_light::LightModes::GLOW;
235  else if(dynamic_cast<XMasMode*>(mode) != NULL)
236  ret = cob_light::LightModes::XMAS;
237  else if(dynamic_cast<KitMode*>(mode) != NULL)
238  ret = cob_light::LightModes::KIT;
239  else if(dynamic_cast<TurnIndicatorMode*>(mode) != NULL)
240  ret = cob_light::LightModes::TURN_LEFT;
241  else if(dynamic_cast<TurnIndicatorMode*>(mode) != NULL)
242  ret = cob_light::LightModes::TURN_RIGHT;
243  else
244  ret = cob_light::LightModes::NONE;
245 
246  return ret;
247 }
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:40
double holdtime
Definition: sequenceMode.h:26


cob_light
Author(s): Benjamin Maidel
autogenerated on Thu Nov 17 2022 03:17:28