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;
47 switch(requestMode.mode)
49 case cob_light::LightModes::STATIC:
50 mode.reset(
new StaticMode(color, requestMode.priority, requestMode.frequency,\
51 requestMode.pulses, requestMode.timeout));
54 case cob_light::LightModes::FLASH:
55 mode.reset(
new FlashMode(color, requestMode.priority, requestMode.frequency,\
56 requestMode.pulses, requestMode.timeout));
59 case cob_light::LightModes::BREATH:
60 mode.reset(
new BreathMode(color, requestMode.priority, requestMode.frequency,\
61 requestMode.pulses, requestMode.timeout));
64 case cob_light::LightModes::BREATH_COLOR:
65 mode.reset(
new BreathColorMode(color, requestMode.priority, requestMode.frequency,\
66 requestMode.pulses, requestMode.timeout));
69 case cob_light::LightModes::FADE_COLOR:
70 mode.reset(
new FadeColorMode(color, requestMode.priority, requestMode.frequency,\
71 requestMode.pulses, requestMode.timeout));
74 case cob_light::LightModes::SEQ:
76 std::vector<seq_t> seqs;
77 for(
size_t i = 0; i < requestMode.sequences.size(); i++)
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;
87 std::cout<<
"got new seq: "<<seq.
color.
r<<
" "<<seq.
color.
g<<
" "<<seq.
color.
b<<std::endl;
89 mode.reset(
new SequenceMode(seqs, requestMode.priority, requestMode.frequency,\
90 requestMode.pulses, requestMode.timeout));
94 case cob_light::LightModes::CIRCLE_COLORS:
96 std::vector<color::rgba> colors;
97 if(requestMode.colors.empty())
99 colors.push_back(color);
103 for(
size_t i = 0; i < requestMode.colors.size(); i++)
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);
113 requestMode.pulses, requestMode.timeout));
117 case cob_light::LightModes::SWEEP:
119 std::vector<color::rgba> colors;
120 if(requestMode.colors.empty())
122 colors.push_back(color);
126 for(
size_t i = 0; i < requestMode.colors.size(); i++)
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);
136 requestMode.pulses, requestMode.timeout));
140 case cob_light::LightModes::DIST_APPROX:
142 requestMode.pulses, requestMode.timeout));
145 case cob_light::LightModes::GLOW:
146 mode.reset(
new GlowColorMode(color, requestMode.priority, requestMode.frequency,\
147 requestMode.pulses, requestMode.timeout));
150 case cob_light::LightModes::XMAS:
151 mode.reset(
new XMasMode(colorO->
getNumLeds(), requestMode.priority, requestMode.frequency,\
152 requestMode.pulses, requestMode.timeout));
166 if(requestMode ==
"Static" || requestMode ==
"static" || requestMode ==
"STATIC")
170 else if(requestMode ==
"Flash" || requestMode ==
"flash" || requestMode ==
"FLASH")
174 else if(requestMode ==
"Breath" || requestMode ==
"breath" || requestMode ==
"BREATH")
178 else if(requestMode ==
"BreathColor" || requestMode ==
"BreathColor" || requestMode ==
"BreathColor" ||
179 requestMode ==
"Breath_Color" || requestMode ==
"breath_color" || requestMode ==
"BREATH_COLOR")
183 else if(requestMode ==
"FadeColor" || requestMode ==
"fadecolor" || requestMode ==
"FADECOLOR" ||
184 requestMode ==
"Fade_Color" || requestMode ==
"fade_color" || requestMode ==
"FADE_COLOR")
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;
222 ret = cob_light::LightModes::NONE;
static int type(Mode *mode)
static boost::shared_ptr< Mode > create(cob_light::LightMode requestMode, IColorO *colorO)