cob_light.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 // standard includes
19 #include <stdio.h>
20 #include <string.h>
21 #include <sstream>
22 #include <math.h>
23 #include <signal.h>
24 
25 // ros includes
26 #include <ros/ros.h>
28 #include <diagnostic_msgs/DiagnosticArray.h>
29 #include <ros/xmlrpc_manager.h>
30 
31 // ros message includes
32 #include <std_msgs/ColorRGBA.h>
33 #include <std_msgs/UInt64.h>
34 #include <visualization_msgs/Marker.h>
35 #include <cob_light/ColorRGBAArray.h>
36 #include <cob_light/LightMode.h>
37 #include <cob_light/LightModes.h>
38 #include <cob_light/SetLightMode.h>
39 #include <cob_light/SetLightModeAction.h>
40 #include <cob_light/SetLightModeActionGoal.h>
41 #include <cob_light/SetLightModeActionResult.h>
42 #include <cob_light/StopLightMode.h>
43 
44 // serial connection includes
45 #include <serialIO.h>
46 
47 // additional includes
48 #include <colorUtils.h>
49 #include <modeExecutor.h>
50 #include <colorO.h>
51 #include <colorOMarker.h>
52 #include <colorOSim.h>
53 #include <ms35.h>
54 #include <stageprofi.h>
55 
56 sig_atomic_t volatile gShutdownRequest = 0;
57 
58 void sigIntHandler(int signal)
59 {
61 }
62 
64 {
65  int num_params = 0;
67  num_params = params.size();
68  if (num_params > 1)
69  {
70  std::string reason = params[1];
71  ROS_WARN("Shutdown request received. Reason: [%s]", reason.c_str());
72  ::gShutdownRequest = 1; // Set flag
73  }
74 
75  result = ros::xmlrpc::responseInt(1, "", 0);
76 }
77 
79 {
80 public:
83  {
84  }
85  bool init()
86  {
87  bool ret = true;
88  bool invert_output;
89  XmlRpc::XmlRpcValue param_list;
90  std::string startup_mode;
91  p_colorO = NULL;
92  p_modeExecutor = NULL;
93  //diagnostics
94  _pubDiagnostic = _nh.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
96 
97  diagnostic_msgs::DiagnosticStatus status;
98  status.name = ros::this_node::getName();
99 
100  //Get Parameter from Parameter Server
101  _nh = ros::NodeHandle("~");
102  if(!_nh.hasParam("invert_output"))
103  ROS_WARN("Parameter 'invert_output' is missing. Using default Value: false");
104  _nh.param<bool>("invert_output", invert_output, false);
105  _invertMask = (int)invert_output;
106 
107  if(!_nh.hasParam("devicedriver"))
108  ROS_WARN("Parameter 'devicedriver' is missing. Using default Value: cob_ledboard");
109  _nh.param<std::string>("devicedriver",_deviceDriver,"cob_ledboard");
110 
111  if(!_nh.hasParam("devicestring"))
112  ROS_WARN("Parameter 'devicestring' is missing. Using default Value: /dev/ttyLed");
113  _nh.param<std::string>("devicestring",_deviceString,"/dev/ttyLed");
114 
115  if(!_nh.hasParam("baudrate"))
116  ROS_WARN("Parameter 'baudrate' is missing. Using default Value: 230400");
117  _nh.param<int>("baudrate",_baudrate,230400);
118 
119  if(!_nh.hasParam("pubmarker"))
120  ROS_WARN("Parameter 'pubmarker' is missing. Using default Value: true");
121  _nh.param<bool>("pubmarker",_bPubMarker,true);
122 
123  if(!_nh.hasParam("marker_frame"))
124  ROS_WARN("Parameter 'marker_frame' is missing. Using default Value: /base_link");
125  _nh.param<std::string>("marker_frame",_sMarkerFrame,"base_link");
126 
127  if(!_nh.hasParam("sim_enabled"))
128  ROS_WARN("Parameter 'sim_enabled' is missing. Using default Value: false");
129  _nh.param<bool>("sim_enabled", _bSimEnabled, false);
130 
131  if(!_nh.hasParam("startup_color"))
132  {
133  ROS_WARN("Parameter 'startup_color' is missing. Using default Value: off");
134  _color.r=0;_color.g=0;_color.b=0;_color.a=0;
135  }
136  else
137  {
138  _nh.getParam("startup_color", param_list);
140  ROS_ASSERT(param_list.size() == 4);
141 
142  _color.r = static_cast<double>(param_list[0]);
143  _color.g = static_cast<double>(param_list[1]);
144  _color.b = static_cast<double>(param_list[2]);
145  _color.a = static_cast<double>(param_list[3]);
146  }
147 
148  if(!_nh.hasParam("startup_mode"))
149  ROS_WARN("Parameter 'startup_mode' is missing. Using default Value: None");
150  _nh.param<std::string>("startup_mode", startup_mode, "None");
151 
152  if(!_nh.hasParam("num_leds"))
153  ROS_WARN("Parameter 'num_leds' is missing. Using default Value: 58");
154  _nh.param<int>("num_leds", _num_leds, 58);
155 
156  int led_offset;
157  _nh.param<int>("led_offset", led_offset, 0);
158 
159  //Subscribe to LightController Command Topic
160  _sub = _nh.subscribe("command", 1, &LightControl::topicCallback, this);
161 
162  //Advertise light mode Service
164 
165  //Advertise stop mode service
167 
168  //Start light mode Action Server
169  _as = new ActionServer(_nh, "set_light", boost::bind(&LightControl::actionCallback, this, _1), false);
170  _as->start();
171 
172  //Advertise visualization marker topic
173  _pubMarker = _nh.advertise<visualization_msgs::Marker>("marker",1);
174 
175  if(!_bSimEnabled)
176  {
177  //open serial port
178  ROS_INFO("Open Port on %s",_deviceString.c_str());
180  {
181  ROS_INFO("Serial connection on %s succeeded.", _deviceString.c_str());
182  status.level = 0;
183  status.message = "light controller running";
184 
185  if(_deviceDriver == "cob_ledboard")
186  p_colorO = new ColorO(&_serialIO);
187  else if(_deviceDriver == "ms-35")
188  p_colorO = new MS35(&_serialIO);
189  else if(_deviceDriver == "stageprofi")
190  p_colorO = new StageProfi(&_serialIO, _num_leds, led_offset);
191  else
192  {
193  ROS_ERROR_STREAM("Unsupported devicedriver ["<<_deviceDriver<<"], falling back to sim mode");
194  p_colorO = new ColorOSim(&_nh);
195  status.level = 2;
196  status.message = "Unsupported devicedriver. Running in simulation mode";
197  }
199  if(!p_colorO->init())
200  {
201  status.level = 3;
202  status.message = "Initializing connection to driver failed";
203  ROS_ERROR("Initializing connection to driver failed. Exiting");
204  ret = false;
205  }
206  }
207  else
208  {
209  ROS_WARN("Serial connection on %s failed.", _deviceString.c_str());
210  ROS_WARN("Simulation mode enabled");
211  p_colorO = new ColorOSim(&_nh);
213 
214  status.level = 2;
215  status.message = "Serial connection failed. Running in simulation mode";
216  }
217  }
218  else
219  {
220  ROS_INFO("Simulation mode enabled");
221  if(_deviceDriver == "markers")
222  {
223  p_colorO = new ColorOMarker(&_nh);
225  }
226  else
227  {
228  p_colorO = new ColorOSim(&_nh);
230  }
231  status.level = 0;
232  status.message = "light controller running in simulation";
233  }
234 
235  _diagnostics.status.push_back(status);
236 
237  if(!ret)
238  return false;
239 
240  if(_bPubMarker)
241  p_colorO->signalColorSet()->connect(boost::bind(&LightControl::markerCallback, this, _1));
242 
244 
245  boost::shared_ptr<Mode> mode = ModeFactory::create(startup_mode, _color);
246  if(mode == NULL)
247  {
249  }
250  else
251  p_modeExecutor->execute(mode);
252 
253  return true;
254  }
255 
257  {
258  if(p_modeExecutor != NULL)
259  {
260  p_modeExecutor->stop();
261  delete p_modeExecutor;
262  }
263  if(p_colorO != NULL)
264  {
265  delete p_colorO;
266  }
267  }
268 
269  void topicCallback(cob_light::ColorRGBAArray color)
270  {
271  boost::mutex::scoped_lock lock(_mutex);
273  {
275  if(color.colors.size() > 0)
276  {
277  if(color.colors.size() > 1)
278  {
279  if(color.colors.size() <= p_colorO->getNumLeds())
280  {
281  std::vector<color::rgba> colors;
282  for(size_t i=0; i<color.colors.size();i++)
283  {
284  if(color.colors[i].r <= 1.0 && color.colors[i].g <= 1.0 && color.colors[i].b <= 1.0)
285  {
286  _color.a = color.colors[i].a;
287  _color.r = color.colors[i].r;
288  _color.g = color.colors[i].g;
289  _color.b = color.colors[i].b;
290  colors.push_back(_color);
291  }
292  else
293  ROS_ERROR("Unsupported Color format. rgba values range is between 0.0 - 1.0");
294  }
295  p_colorO->setColorMulti(colors);
296  }
297  else
298  ROS_ERROR_STREAM("More colors given in ColorRGBAArray ("<<color.colors.size()<<") then driver is configured ("<<p_colorO->getNumLeds()<<"). num leds: "<<_num_leds);
299  }
300  else
301  {
302  if(color.colors[0].r <= 1.0 && color.colors[0].g <= 1.0 && color.colors[0].b <= 1.0)
303  {
304  _color.r = color.colors[0].r;
305  _color.g = color.colors[0].g;
306  _color.b = color.colors[0].b;
307  _color.a = color.colors[0].a;
308 
310  }
311  else
312  ROS_ERROR("Unsupported Color format. rgba values range is between 0.0 - 1.0");
313  }
314  }
315  else
316  ROS_ERROR("Empty color msg received");
317  }
318  }
319 
320  bool serviceCallback(cob_light::SetLightMode::Request &req, cob_light::SetLightMode::Response &res)
321  {
322  boost::mutex::scoped_lock lock(_mutex);
323  bool ret = false;
324 
325  //ROS_DEBUG("Service Callback [Mode: %i with prio: %i freq: %f timeout: %f pulses: %i ] [R: %f with G: %f B: %f A: %f]",
326  // req.mode.mode, req.mode.priority, req.mode.frequency, req.mode.timeout, req.mode.pulses,req.mode.color.r,req.mode.color.g ,req.mode.color.b,req.mode.color.a);
327  if(req.mode.colors.size() > 0)
328  {
329  if(req.mode.colors[0].r > 1.0 || req.mode.colors[0].g > 1.0 ||
330  req.mode.colors[0].b > 1.0 || req.mode.colors[0].a > 1.0)
331  {
332  res.active_mode = p_modeExecutor->getExecutingMode();
333  res.active_priority = p_modeExecutor->getExecutingPriority();
334  res.track_id = -1;
335  ROS_ERROR("Unsupported Color format. rgba values range is between 0.0 - 1.0");
336  }
337  else if(req.mode.mode == cob_light::LightModes::NONE) //refactor this
338  {
339  p_modeExecutor->stop();
340  _color.a = 0;
341  //p_modeExecutor->execute(req.mode);
343  res.active_mode = p_modeExecutor->getExecutingMode();
344  res.active_priority = p_modeExecutor->getExecutingPriority();
345  ret = true;
346  }
347  else
348  {
349  uint64_t u_id = p_modeExecutor->execute(req.mode);
350  res.active_mode = p_modeExecutor->getExecutingMode();
351  res.active_priority = p_modeExecutor->getExecutingPriority();
352  res.track_id = u_id;
353  ret = true;
354  }
355  }
356  return ret;
357  }
358 
359  void actionCallback(const cob_light::SetLightModeGoalConstPtr &goal)
360  {
361  boost::mutex::scoped_lock lock(_mutex);
362  cob_light::SetLightModeResult result;
363  if(goal->mode.colors.size() > 0)
364  {
365  if(goal->mode.colors[0].r > 1.0 || goal->mode.colors[0].g > 1.0 ||
366  goal->mode.colors[0].b > 1.0 || goal->mode.colors[0].a > 1.0)
367  {
368  result.active_mode = p_modeExecutor->getExecutingMode();
369  result.active_priority = p_modeExecutor->getExecutingPriority();
370  result.track_id = -1;
371  _as->setAborted(result, "Unsupported Color format. rgba values range is between 0.0 - 1.0");
372 
373  ROS_ERROR("Unsupported Color format. rgba values range is between 0.0 - 1.0");
374  }
375  else if(goal->mode.mode == cob_light::LightModes::NONE)
376  {
377  p_modeExecutor->stop();
378  _color.a = 0;
380  result.active_mode = p_modeExecutor->getExecutingMode();
381  result.active_priority = p_modeExecutor->getExecutingPriority();
382  result.track_id = -1;
383  _as->setSucceeded(result, "Mode switched");
384  }
385  else
386  {
387  uint64_t u_id = p_modeExecutor->execute(goal->mode);
388  result.active_mode = p_modeExecutor->getExecutingMode();
389  result.active_priority = p_modeExecutor->getExecutingPriority();
390  result.track_id = u_id;
391  _as->setSucceeded(result, "Mode switched");
392  }
393  }
394  else
395  _as->setAborted(result, "No color available");
396  }
397 
398  bool stopMode(cob_light::StopLightMode::Request &req, cob_light::StopLightMode::Response &res)
399  {
400  boost::mutex::scoped_lock lock(_mutex);
401  bool ret = false;
402  ret = p_modeExecutor->stop(req.track_id);
403  res.active_mode = p_modeExecutor->getExecutingMode();
404  res.active_priority = p_modeExecutor->getExecutingPriority();
405  res.track_id = p_modeExecutor->getExecutingUId();
406  ret = true; // TODO: really check if mode is stopped
407  return ret;
408  }
409 
411  {
412  _diagnostics.header.stamp = ros::Time::now();
414  }
415 
417  {
418  visualization_msgs::Marker marker;
419  marker.header.frame_id = _sMarkerFrame;
420  marker.header.stamp = ros::Time();
421  marker.ns = "color";
422  marker.id = 0;
423  marker.type = visualization_msgs::Marker::SPHERE;
424  marker.action = visualization_msgs::Marker::ADD;
425  marker.pose.position.x = 0.5;
426  marker.pose.position.y = 0.0;
427  marker.pose.position.z = 0.0;
428  marker.pose.orientation.x = 0.0;
429  marker.pose.orientation.y = 0.0;
430  marker.pose.orientation.z = 0.0;
431  marker.pose.orientation.w = 1.0;
432  marker.scale.x = 0.1;
433  marker.scale.y = 0.1;
434  marker.scale.z = 0.1;
435  marker.color.a = color.a;
436  marker.color.r = color.r;
437  marker.color.g = color.g;
438  marker.color.b = color.b;
439  _pubMarker.publish(marker);
440  }
441 
442 private:
443  std::string _deviceDriver;
444  std::string _deviceString;
448  std::string _sMarkerFrame;
451 
453 
460 
461  diagnostic_msgs::DiagnosticArray _diagnostics;
464 
467 
469 
473 
474  boost::mutex _mutex;
475 };
476 
477 int main(int argc, char** argv)
478 {
479  // init node
480  ros::init(argc, argv, "light_controller", ros::init_options::NoSigintHandler);
481  signal(SIGINT, sigIntHandler);
482 
483  // Override XMLRPC shutdown
484  ros::XMLRPCManager::instance()->unbind("shutdown");
485  ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
486 
487  // create LightControl instance
488  LightControl *lightControl = new LightControl();
489  if(lightControl->init())
490  {
492  spinner.start();
493 
494  while (!gShutdownRequest)
495  {
496  ros::Duration(0.05).sleep();
497  }
498 
499  delete lightControl;
500 
501  ros::shutdown();
502  }
503 
504  return 0;
505 }
XmlRpc::XmlRpcValue::size
int size() const
LightControl::_sub
ros::Subscriber _sub
Definition: cob_light.cpp:455
LightControl::stopMode
bool stopMode(cob_light::StopLightMode::Request &req, cob_light::StopLightMode::Response &res)
Definition: cob_light.cpp:398
ros::Publisher
ModeExecutor::pause
void pause()
Definition: modeExecutor.cpp:88
LightControl::init
bool init()
Definition: cob_light.cpp:85
LightControl::serviceCallback
bool serviceCallback(cob_light::SetLightMode::Request &req, cob_light::SetLightMode::Response &res)
Definition: cob_light.cpp:320
color
Definition: colorUtils.h:24
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< Mode >
LightControl::_invertMask
int _invertMask
Definition: cob_light.cpp:446
ModeExecutor::stop
void stop()
Definition: modeExecutor.cpp:102
LightControl
Definition: cob_light.cpp:78
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
actionlib::SimpleActionServer::start
void start()
ros::xmlrpc::responseInt
ROSCPP_DECL XmlRpc::XmlRpcValue responseInt(int code, const std::string &msg, int response)
IColorO::setColor
virtual void setColor(color::rgba color)=0
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
IColorO::setMask
void setMask(int mask)
Definition: iColorO.h:34
IColorO::setNumLeds
void setNumLeds(size_t num_leds)
Definition: iColorO.h:35
LightControl::_num_leds
int _num_leds
Definition: cob_light.cpp:450
LightControl::_baudrate
int _baudrate
Definition: cob_light.cpp:445
SerialIO
Definition: serialIO.h:39
ros::AsyncSpinner
LightControl::_as
ActionServer * _as
Definition: cob_light.cpp:466
IColorO::init
virtual bool init()=0
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
main
int main(int argc, char **argv)
Definition: cob_light.cpp:477
colorUtils.h
simple_action_server.h
LightControl::_pubMarker
ros::Publisher _pubMarker
Definition: cob_light.cpp:457
LightControl::actionCallback
void actionCallback(const cob_light::SetLightModeGoalConstPtr &goal)
Definition: cob_light.cpp:359
LightControl::_sMarkerFrame
std::string _sMarkerFrame
Definition: cob_light.cpp:448
LightControl::_bPubMarker
bool _bPubMarker
Definition: cob_light.cpp:447
LightControl::_diagnostics_timer
ros::Timer _diagnostics_timer
Definition: cob_light.cpp:463
LightControl::_color
color::rgba _color
Definition: cob_light.cpp:468
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
actionlib::SimpleActionServer::setSucceeded
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
LightControl::_bSimEnabled
bool _bSimEnabled
Definition: cob_light.cpp:449
ColorOSim
Definition: colorOSim.h:27
LightControl::_deviceDriver
std::string _deviceDriver
Definition: cob_light.cpp:443
ros::ServiceServer
LightControl::_srvServer
ros::ServiceServer _srvServer
Definition: cob_light.cpp:458
spinner
void spinner()
color::rgba
Definition: colorUtils.h:26
LightControl::publish_diagnostics_cb
void publish_diagnostics_cb(const ros::TimerEvent &)
Definition: cob_light.cpp:410
LightControl::_sub_mode
ros::Subscriber _sub_mode
Definition: cob_light.cpp:456
xmlrpc_manager.h
serialIO.h
LightControl::_pubDiagnostic
ros::Publisher _pubDiagnostic
Definition: cob_light.cpp:462
ColorOMarker
Definition: colorOMarker.h:28
IColorO::signalColorSet
boost::signals2::signal< void(color::rgba color)> * signalColorSet()
Definition: iColorO.h:38
LightControl::_deviceString
std::string _deviceString
Definition: cob_light.cpp:444
LightControl::p_modeExecutor
ModeExecutor * p_modeExecutor
Definition: cob_light.cpp:472
LightControl::topicCallback
void topicCallback(cob_light::ColorRGBAArray color)
Definition: cob_light.cpp:269
ms35.h
sigIntHandler
void sigIntHandler(int signal)
Definition: cob_light.cpp:58
color::rgba::g
float g
Definition: colorUtils.h:30
MS35
Definition: ms35.h:27
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
colorOSim.h
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::XMLRPCManager::instance
static const XMLRPCManagerPtr & instance()
ros::TimerEvent
LightControl::ActionServer
actionlib::SimpleActionServer< cob_light::SetLightModeAction > ActionServer
Definition: cob_light.cpp:465
gShutdownRequest
sig_atomic_t volatile gShutdownRequest
Definition: cob_light.cpp:56
color::rgba::b
float b
Definition: colorUtils.h:31
XmlRpc::XmlRpcValue::getType
const Type & getType() const
IColorO
Definition: iColorO.h:24
LightControl::_topic_priority
int _topic_priority
Definition: cob_light.cpp:452
ModeExecutor::getExecutingUId
uint64_t getExecutingUId()
Definition: modeExecutor.cpp:190
LightControl::LightControl
LightControl()
Definition: cob_light.cpp:81
LightControl::~LightControl
~LightControl()
Definition: cob_light.cpp:256
XmlRpc::XmlRpcValue::TypeArray
TypeArray
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
IColorO::setColorMulti
virtual void setColorMulti(std::vector< color::rgba > &colors)=0
ros::Time
actionlib::SimpleActionServer::setAborted
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
color::rgba::r
float r
Definition: colorUtils.h:29
ModeExecutor::execute
uint64_t execute(boost::shared_ptr< Mode > mode)
Definition: modeExecutor.cpp:42
LightControl::_nh
ros::NodeHandle _nh
Definition: cob_light.cpp:454
LightControl::_mutex
boost::mutex _mutex
Definition: cob_light.cpp:474
SerialIO::openPort
int openPort(std::string devicestring, int baudrate)
Definition: serialIO.cpp:37
IColorO::getNumLeds
int getNumLeds()
Definition: iColorO.h:36
colorOMarker.h
ModeExecutor::getExecutingMode
int getExecutingMode()
Definition: modeExecutor.cpp:174
actionlib::SimpleActionServer
ROS_ERROR
#define ROS_ERROR(...)
shutdownCallback
void shutdownCallback(XmlRpc::XmlRpcValue &params, XmlRpc::XmlRpcValue &result)
Definition: cob_light.cpp:63
ModeFactory::create
static boost::shared_ptr< Mode > create(cob_light::LightMode requestMode, IColorO *colorO)
Definition: modeFactory.cpp:40
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
LightControl::markerCallback
void markerCallback(color::rgba color)
Definition: cob_light.cpp:416
ModeExecutor::getExecutingPriority
int getExecutingPriority()
Definition: modeExecutor.cpp:182
ColorO
Definition: colorO.h:27
stageprofi.h
ros::Duration::sleep
bool sleep() const
color::rgba::a
float a
Definition: colorUtils.h:32
LightControl::_serialIO
SerialIO _serialIO
Definition: cob_light.cpp:471
StageProfi
Definition: stageprofi.h:27
ROS_INFO
#define ROS_INFO(...)
ROS_ASSERT
#define ROS_ASSERT(cond)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
colorO.h
ros::Timer
ros::init_options::NoSigintHandler
NoSigintHandler
LightControl::_srvStopMode
ros::ServiceServer _srvStopMode
Definition: cob_light.cpp:459
ModeExecutor
Definition: modeExecutor.h:28
LightControl::_diagnostics
diagnostic_msgs::DiagnosticArray _diagnostics
Definition: cob_light.cpp:461
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()
modeExecutor.h
LightControl::p_colorO
IColorO * p_colorO
Definition: cob_light.cpp:470


cob_light
Author(s): Benjamin Maidel
autogenerated on Wed Nov 8 2023 03:47:37