colorOSim.cpp
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 #include <colorOSim.h>
00018 #include <std_msgs/ColorRGBA.h>
00019 #include <cob_light/ColorRGBAArray.h>
00020 
00021 ColorOSim::ColorOSim(ros::NodeHandle* nh)
00022 {
00023   p_nh = nh;
00024   _pubSimulation = p_nh->advertise<std_msgs::ColorRGBA>("debug",2);
00025   _pubSimulationMulti = p_nh->advertise<cob_light::ColorRGBAArray>("debugMulti", 2);
00026 }
00027 
00028 ColorOSim::~ColorOSim()
00029 {
00030 }
00031 
00032 bool ColorOSim::init()
00033 {
00034   return true;
00035 }
00036 
00037 void ColorOSim::setColor(color::rgba color)
00038 {
00039   std_msgs::ColorRGBA _color;
00040   _color.r = color.r;
00041   _color.g = color.g;
00042   _color.b = color.b;
00043   _color.a = color.a;
00044 
00045   _pubSimulation.publish(_color);
00046   m_sigColorSet(color);
00047 }
00048 
00049 void ColorOSim::setColorMulti(std::vector<color::rgba> &colors)
00050 {
00051   std_msgs::ColorRGBA color;
00052   cob_light::ColorRGBAArray colorMsg;
00053   for(size_t i = 0; i < colors.size(); ++i)
00054   {
00055     color.r = colors[i].r;
00056     color.g = colors[i].g;
00057     color.b = colors[i].b;
00058     color.a = colors[i].a;
00059     colorMsg.colors.push_back(color);
00060   }
00061 
00062   _pubSimulationMulti.publish(colorMsg);
00063   m_sigColorSet(colors[0]);
00064 }


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