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


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