colorOSim.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 #include <colorOSim.h>
18 #include <std_msgs/ColorRGBA.h>
19 #include <cob_light/ColorRGBAArray.h>
20 
22 {
23  p_nh = nh;
24  _pubSimulation = p_nh->advertise<std_msgs::ColorRGBA>("debug",2);
25  _pubSimulationMulti = p_nh->advertise<cob_light::ColorRGBAArray>("debugMulti", 2);
26 }
27 
29 {
30 }
31 
33 {
34  return true;
35 }
36 
38 {
39  std_msgs::ColorRGBA _color;
40  _color.r = color.r;
41  _color.g = color.g;
42  _color.b = color.b;
43  _color.a = color.a;
44 
45  _pubSimulation.publish(_color);
46  m_sigColorSet(color);
47 }
48 
49 void ColorOSim::setColorMulti(std::vector<color::rgba> &colors)
50 {
51  std_msgs::ColorRGBA color;
52  cob_light::ColorRGBAArray colorMsg;
53  for(size_t i = 0; i < colors.size(); ++i)
54  {
55  color.r = colors[i].r;
56  color.g = colors[i].g;
57  color.b = colors[i].b;
58  color.a = colors[i].a;
59  colorMsg.colors.push_back(color);
60  }
61 
62  _pubSimulationMulti.publish(colorMsg);
63  m_sigColorSet(colors[0]);
64 }
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher _pubSimulation
Definition: colorOSim.h:39
ColorOSim(ros::NodeHandle *nh)
Definition: colorOSim.cpp:21
bool init()
Definition: colorOSim.cpp:32
void setColor(color::rgba color)
Definition: colorOSim.cpp:37
ros::Publisher _pubSimulationMulti
Definition: colorOSim.h:40
void setColorMulti(std::vector< color::rgba > &colors)
Definition: colorOSim.cpp:49
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual ~ColorOSim()
Definition: colorOSim.cpp:28
boost::signals2::signal< void(color::rgba color)> m_sigColorSet
Definition: iColorO.h:45
ros::NodeHandle * p_nh
Definition: colorOSim.h:38


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