28 #include <diagnostic_msgs/DiagnosticArray.h>    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>    66     num_params = params.
size();
    69     std::string reason = params[1];
    70     ROS_WARN(
"Shutdown request received. Reason: [%s]", reason.c_str());
    89     std::string startup_mode;
    96     diagnostic_msgs::DiagnosticStatus status;
   102       ROS_WARN(
"Parameter 'invert_output' is missing. Using default Value: false");
   103     _nh.
param<
bool>(
"invert_output", invert_output, 
false);
   107       ROS_WARN(
"Parameter 'devicedriver' is missing. Using default Value: cob_ledboard");
   111       ROS_WARN(
"Parameter 'devicestring' is missing. Using default Value: /dev/ttyLed");
   115       ROS_WARN(
"Parameter 'baudrate' is missing. Using default Value: 230400");
   119       ROS_WARN(
"Parameter 'pubmarker' is missing. Using default Value: true");
   123       ROS_WARN(
"Parameter 'marker_frame' is missing. Using default Value: /base_link");
   127       ROS_WARN(
"Parameter 'sim_enabled' is missing. Using default Value: false");
   132       ROS_WARN(
"Parameter 'startup_color' is missing. Using default Value: off");
   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]);
   148       ROS_WARN(
"Parameter 'startup_mode' is missing. Using default Value: None");
   149     _nh.
param<std::string>(
"startup_mode", startup_mode, 
"None");
   152             ROS_WARN(
"Parameter 'num_leds' is missing. Using default Value: 58");
   156     _nh.
param<
int>(
"led_offset", led_offset, 0);
   177       ROS_INFO(
"Open Port on %s",_deviceString.c_str());
   180         ROS_INFO(
"Serial connection on %s succeeded.", _deviceString.c_str());
   182         status.message = 
"light controller running";
   184         if(_deviceDriver == 
"cob_ledboard")
   186         else if(_deviceDriver == 
"ms-35")
   188         else if(_deviceDriver == 
"stageprofi")
   192           ROS_ERROR_STREAM(
"Unsupported devicedriver ["<<_deviceDriver<<
"], falling back to sim mode");
   195           status.message = 
"Unsupported devicedriver. Running in simulation mode";
   201           status.message = 
"Initializing connection to driver failed";
   202           ROS_ERROR(
"Initializing connection to driver failed. Exiting");
   208         ROS_WARN(
"Serial connection on %s failed.", _deviceString.c_str());
   209         ROS_WARN(
"Simulation mode enabled");
   214         status.message = 
"Serial connection failed. Running in simulation mode";
   219       ROS_INFO(
"Simulation mode enabled");
   223       status.message = 
"light controller running in simulation";
   262       boost::mutex::scoped_lock lock(
_mutex);
   266           if(color.colors.size() > 0)
   268               if(color.colors.size() > 1)
   272                     std::vector<color::rgba> colors;
   273                     for(
size_t i=0; i<color.colors.size();i++)
   275                         if(color.colors[i].r <= 1.0 && color.colors[i].g <= 1.0 && color.colors[i].b <= 1.0)
   284                           ROS_ERROR(
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
   293                   if(color.colors[0].r <= 1.0 && color.colors[0].g <= 1.0 && color.colors[0].b <= 1.0)
   303                     ROS_ERROR(
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
   311   bool serviceCallback(cob_light::SetLightMode::Request &req, cob_light::SetLightMode::Response &res)
   313     boost::mutex::scoped_lock lock(
_mutex);
   318     if(req.mode.colors.size() > 0)
   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)
   326           ROS_ERROR(
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
   328         else if(req.mode.mode == cob_light::LightModes::NONE) 
   352     boost::mutex::scoped_lock lock(
_mutex);
   353     cob_light::SetLightModeResult result;
   354     if(goal->mode.colors.size() > 0)
   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)
   361           result.track_id = -1;
   362           _as->
setAborted(result, 
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
   364           ROS_ERROR(
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
   366         else if(goal->mode.mode == cob_light::LightModes::NONE)
   373           result.track_id = -1;
   381           result.track_id = u_id;
   389   bool stopMode(cob_light::StopLightMode::Request &req, cob_light::StopLightMode::Response &res)
   391       boost::mutex::scoped_lock lock(
_mutex);
   409     visualization_msgs::Marker marker;
   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;
   468 int main(
int argc, 
char** argv)
   480   if(lightControl->
init())
 void setNumLeds(size_t num_leds)
bool stopMode(cob_light::StopLightMode::Request &req, cob_light::StopLightMode::Response &res)
void actionCallback(const cob_light::SetLightModeGoalConstPtr &goal)
std::string _sMarkerFrame
int openPort(std::string devicestring, int baudrate)
ros::Publisher _pubDiagnostic
void publish(const boost::shared_ptr< M > &message) const 
void topicCallback(cob_light::ColorRGBAArray color)
void shutdownCallback(XmlRpc::XmlRpcValue ¶ms, XmlRpc::XmlRpcValue &result)
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)
boost::signals2::signal< void(color::rgba color)> * signalColorSet()
void publish_diagnostics_cb(const ros::TimerEvent &)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sig_atomic_t volatile gShutdownRequest
ROSCPP_DECL const std::string & getName()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Type const & getType() const 
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ros::Publisher _pubMarker
int getExecutingPriority()
ros::ServiceServer _srvServer
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
ros::Subscriber _sub_mode
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const 
void markerCallback(color::rgba color)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint64_t execute(boost::shared_ptr< Mode > mode)
ModeExecutor * p_modeExecutor
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
ros::ServiceServer _srvStopMode
diagnostic_msgs::DiagnosticArray _diagnostics
virtual void setColorMulti(std::vector< color::rgba > &colors)=0
bool getParam(const std::string &key, std::string &s) const 
static const XMLRPCManagerPtr & instance()
ROSCPP_DECL void shutdown()
actionlib::SimpleActionServer< cob_light::SetLightModeAction > ActionServer
ros::Timer _diagnostics_timer
uint64_t getExecutingUId()
virtual void setColor(color::rgba color)=0
bool hasParam(const std::string &key) const 
#define ROS_ERROR_STREAM(args)
void sigIntHandler(int signal)
std::string _deviceString
bool serviceCallback(cob_light::SetLightMode::Request &req, cob_light::SetLightMode::Response &res)
std::string _deviceDriver
static boost::shared_ptr< Mode > create(cob_light::LightMode requestMode, IColorO *colorO)