00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 
00042 
00043 
00044 
00045 
00046 
00047 
00048 
00049 
00050 
00051 
00052 
00053 
00054 
00055 
00056 #include <stdio.h>
00057 #include <string.h>
00058 #include <sstream>
00059 #include <math.h>
00060 #include <signal.h>
00061 
00062 
00063 #include <ros/ros.h>
00064 #include <actionlib/server/simple_action_server.h>
00065 #include <diagnostic_msgs/DiagnosticArray.h>
00066 #include <ros/xmlrpc_manager.h>
00067 
00068 
00069 #include <std_msgs/ColorRGBA.h>
00070 #include <visualization_msgs/Marker.h>
00071 #include <cob_light/LightMode.h>
00072 #include <cob_light/SetLightMode.h>
00073 #include <cob_light/SetLightModeAction.h>
00074 #include <cob_light/SetLightModeActionGoal.h>
00075 #include <cob_light/SetLightModeActionResult.h>
00076 
00077 
00078  #include <serialIO.h>
00079 
00080 
00081 #include <colorUtils.h>
00082 #include <modeExecutor.h>
00083 #include <colorO.h>
00084 #include <colorOSim.h>
00085 
00086 sig_atomic_t volatile gShutdownRequest = 0;
00087 
00088 void sigIntHandler(int signal)
00089 {
00090   ::gShutdownRequest = 1;
00091 }
00092 
00093 void shutdownCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
00094 {
00095   int num_params = 0;
00096   if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
00097     num_params = params.size();
00098   if (num_params > 1)
00099   {
00100     std::string reason = params[1];
00101     ROS_WARN("Shutdown request received. Reason: [%s]", reason.c_str());
00102     ::gShutdownRequest = 1; 
00103   }
00104 
00105   result = ros::xmlrpc::responseInt(1, "", 0);
00106 }
00107 
00108 class LightControl
00109 {
00110         public:
00111                 LightControl() :
00112                  _invertMask(0), _topic_priority(0)
00113                 {
00114                         bool invert_output;
00115                         XmlRpc::XmlRpcValue param_list;
00116                         std::string startup_mode;
00117                         p_colorO = NULL;
00118                         p_modeExecutor = NULL;
00119 
00120                         
00121                         _pubDiagnostic = _nh.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
00122 
00123                         diagnostic_msgs::DiagnosticStatus status;
00124                 status.name = "light";
00125                 
00126 
00127                         
00128                         _nh = ros::NodeHandle("~");
00129                         if(!_nh.hasParam("invert_output"))
00130                                 ROS_WARN("Parameter 'invert_output' is missing. Using default Value: false");
00131                         _nh.param<bool>("invert_output", invert_output, false);
00132                         _invertMask = (int)invert_output;
00133 
00134                         if(!_nh.hasParam("devicestring"))
00135                                 ROS_WARN("Parameter 'devicestring' is missing. Using default Value: /dev/ttyLed");
00136                         _nh.param<std::string>("devicestring",_deviceString,"/dev/ttyLed");
00137 
00138                         if(!_nh.hasParam("baudrate"))
00139                                 ROS_WARN("Parameter 'baudrate' is missing. Using default Value: 230400");
00140                         _nh.param<int>("baudrate",_baudrate,230400);
00141 
00142                         if(!_nh.hasParam("pubmarker"))
00143                                 ROS_WARN("Parameter 'pubmarker' is missing. Using default Value: true");
00144                         _nh.param<bool>("pubmarker",_bPubMarker,true);
00145 
00146                         if(!_nh.hasParam("sim_enabled"))
00147                                 ROS_WARN("Parameter 'sim_enabled' is missing. Using default Value: false");
00148                         _nh.param<bool>("sim_enabled", _bSimEnabled, false);
00149 
00150                         if(!_nh.hasParam("startup_color"))
00151                         {
00152                                 ROS_WARN("Parameter 'startup_color' is missing. Using default Value: off");
00153                                 _color.r=0;_color.g=0;_color.b=0;_color.a=0;
00154                         }
00155                         else
00156                         {
00157                                 _nh.getParam("startup_color", param_list);
00158                                 ROS_ASSERT(param_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00159                                 ROS_ASSERT(param_list.size() == 4);
00160 
00161                                 _color.r = static_cast<double>(param_list[0]);
00162                                 _color.g = static_cast<double>(param_list[1]);
00163                                 _color.b = static_cast<double>(param_list[2]);
00164                                 _color.a = static_cast<double>(param_list[3]);
00165                         }
00166 
00167                         if(!_nh.hasParam("startup_mode"))
00168                                 ROS_WARN("Parameter 'startup_mode' is missing. Using default Value: None");
00169                         _nh.param<std::string>("startup_mode", startup_mode, "None");
00170 
00171                         
00172                         _sub = _nh.subscribe("command", 1, &LightControl::topicCallback, this);
00173 
00174                         
00175                         _srvServer = _nh.advertiseService("mode", &LightControl::serviceCallback, this);
00176 
00177                         
00178                         _as = new ActionServer(_nh, "set_lightmode", boost::bind(&LightControl::actionCallback, this, _1), false);
00179                         _as->start();
00180 
00181                         
00182                         _pubMarker = _nh.advertise<visualization_msgs::Marker>("marker",1);
00183 
00184                         if(!_bSimEnabled)
00185                         {
00186                                 
00187                                 ROS_INFO("Open Port on %s",_deviceString.c_str());
00188                                 if(_serialIO.openPort(_deviceString, _baudrate) != -1)
00189                                 {
00190                                         ROS_INFO("Serial connection on %s succeeded.", _deviceString.c_str());
00191                                         p_colorO = new ColorO(&_serialIO);
00192                                         p_colorO->setMask(_invertMask);
00193 
00194                                         status.level = 0;
00195                                         status.message = "light controller running";
00196                                 }
00197                                 else
00198                                 {
00199                                         ROS_WARN("Serial connection on %s failed.", _deviceString.c_str());
00200                                         ROS_INFO("Simulation Mode Enabled");
00201                                         p_colorO = new ColorOSim(&_nh);
00202 
00203                                         status.level = 2;
00204                                         status.message = "Serial connection failed. Running in simulation mode";
00205                                 }
00206                         }
00207                         else
00208                         {
00209                                 ROS_INFO("Simulation Mode Enabled");
00210                                 p_colorO = new ColorOSim(&_nh);
00211                                 status.level = 0;
00212                                 status.message = "light controller running in simulation";
00213                         }
00214                 
00215                 _diagnostics.status.push_back(status);
00216                 _diagnostics.header.stamp = ros::Time::now();
00217                 _pubDiagnostic.publish(_diagnostics);
00218                 _diagnostics.status.resize(0);
00219 
00220                         if(_bPubMarker)
00221                                 p_colorO->signalColorSet()->connect(boost::bind(&LightControl::markerCallback, this, _1));
00222 
00223                         p_modeExecutor = new ModeExecutor(p_colorO);
00224 
00225                         Mode * mode = ModeFactory::create(startup_mode, _color);
00226                         if(mode == NULL)
00227                                 p_colorO->setColor(_color);
00228                         else
00229                                 p_modeExecutor->execute(mode);
00230                 }
00231 
00232                 ~LightControl()
00233                 {
00234                         if(p_modeExecutor != NULL)
00235                         {
00236                                 p_modeExecutor->stop();
00237                                 delete p_modeExecutor;
00238                         }
00239                         if(p_colorO != NULL)
00240                         {
00241                                 delete p_colorO;
00242                         }
00243                 }
00244 
00245                 void topicCallback(std_msgs::ColorRGBA color)
00246                 {
00247                         if(color.r <= 1.0 && color.g <=1.0 && color.b <= 1.0)
00248                         {
00249                                 if(p_modeExecutor->getExecutingPriority() <= _topic_priority)
00250                                 {
00251                                         p_modeExecutor->stop();
00252                                         _color.r = color.r;
00253                                         _color.g = color.g;
00254                                         _color.b = color.b;
00255                                         _color.a = color.a;
00256                                         p_colorO->setColor(_color);
00257                                 }
00258                         }
00259                         else
00260                                 ROS_ERROR("Unsupported Color format. rgba values range is between 0.0 - 1.0");
00261                 }
00262 
00263                 bool serviceCallback(cob_light::SetLightMode::Request &req, cob_light::SetLightMode::Response &res)
00264                 {
00265                         bool ret = false;
00266 
00267                         
00268                         
00269 
00270                         if(req.mode.color.r > 1.0 || req.mode.color.g > 1.0 || req.mode.color.b > 1.0 || req.mode.color.a > 1.0)
00271                         {
00272                                 res.active_mode = p_modeExecutor->getExecutingMode();
00273                                 res.active_priority = p_modeExecutor->getExecutingPriority();
00274                                 ROS_ERROR("Unsupported Color format. rgba values range is between 0.0 - 1.0");
00275                         }
00276                         else if(req.mode.mode == cob_light::LightMode::NONE)
00277                         {
00278                                 p_modeExecutor->stop();
00279                                 _color.a = 0;
00280                                 p_colorO->setColor(_color);
00281                                 res.active_mode = p_modeExecutor->getExecutingMode();
00282                                 res.active_priority = p_modeExecutor->getExecutingPriority();
00283                                 ret = true;
00284                         }
00285                         else
00286                         {
00287                                 p_modeExecutor->execute(req.mode);
00288                                 res.active_mode = p_modeExecutor->getExecutingMode();
00289                                 res.active_priority = p_modeExecutor->getExecutingPriority();
00290                                 ret = true;
00291                         }
00292                         
00293                         return ret;
00294                 }
00295 
00296                 void actionCallback(const cob_light::SetLightModeGoalConstPtr &goal)
00297                 {
00298                         cob_light::SetLightModeResult result;
00299                         if(goal->mode.color.r > 1.0 || goal->mode.color.g > 1.0 || goal->mode.color.b > 1.0 || goal->mode.color.a > 1.0)
00300                         {
00301                                 result.active_mode = p_modeExecutor->getExecutingMode();
00302                                 result.active_priority = p_modeExecutor->getExecutingPriority();
00303                                 _as->setAborted(result, "Unsupported Color format. rgba values range is between 0.0 - 1.0");
00304                                 
00305                                 ROS_ERROR("Unsupported Color format. rgba values range is between 0.0 - 1.0");
00306                         }
00307                         else if(goal->mode.mode == cob_light::LightMode::NONE)
00308                         {
00309                                 p_modeExecutor->stop();
00310                                 _color.a = 0;
00311                                 p_colorO->setColor(_color);
00312 
00313                                 result.active_mode = p_modeExecutor->getExecutingMode();
00314                                 result.active_priority = p_modeExecutor->getExecutingPriority();
00315                                 _as->setSucceeded(result, "Mode switched");
00316                         }
00317                         else
00318                         {
00319                                 p_modeExecutor->execute(goal->mode);
00320                                 result.active_mode = p_modeExecutor->getExecutingMode();
00321                                 result.active_priority = p_modeExecutor->getExecutingPriority();
00322                                 _as->setSucceeded(result, "Mode switched");
00323                         }
00324                 }
00325 
00326                 void markerCallback(color::rgba color)
00327                 {
00328                         visualization_msgs::Marker marker;
00329                         marker.header.frame_id = "/base_link";
00330                         marker.header.stamp = ros::Time();
00331                         marker.ns = "color";
00332                         marker.id = 0;
00333                         marker.type = visualization_msgs::Marker::SPHERE;
00334                         marker.action = visualization_msgs::Marker::ADD;
00335                         marker.pose.position.x = 0;
00336                         marker.pose.position.y = 0,
00337                         marker.pose.position.z = 1.5;
00338                         marker.pose.orientation.x = 0.0;
00339                         marker.pose.orientation.y = 0.0;
00340                         marker.pose.orientation.z = 0.0;
00341                         marker.pose.orientation.w = 1.0;
00342                         marker.scale.x = 0.1;
00343                         marker.scale.y = 0.1;
00344                         marker.scale.z = 0.1;
00345                         marker.color.a = color.a;
00346                         marker.color.r = color.r;
00347                         marker.color.g = color.g;
00348                         marker.color.b = color.b;
00349                         _pubMarker.publish(marker);
00350                 }
00351                 
00352         private:
00353                 std::string _deviceString;
00354                 int _baudrate;
00355                 int _invertMask;
00356                 bool _bPubMarker;
00357                 bool _bSimEnabled;
00358 
00359                 int _topic_priority;
00360 
00361                 ros::NodeHandle _nh;
00362                 ros::Subscriber _sub;
00363                 ros::Publisher _pubMarker;
00364                 ros::ServiceServer _srvServer;
00365 
00366                 diagnostic_msgs::DiagnosticArray _diagnostics;
00367                 ros::Publisher _pubDiagnostic;
00368 
00369                 typedef actionlib::SimpleActionServer<cob_light::SetLightModeAction> ActionServer;
00370                 ActionServer *_as;
00371 
00372                 color::rgba _color;
00373                 
00374                 IColorO* p_colorO;
00375                 SerialIO _serialIO;
00376                 ModeExecutor* p_modeExecutor;
00377 };
00378 
00379 int main(int argc, char** argv)
00380 {
00381         
00382         ros::init(argc, argv, "light_controller", ros::init_options::NoSigintHandler);
00383         signal(SIGINT, sigIntHandler);
00384 
00385         
00386         ros::XMLRPCManager::instance()->unbind("shutdown");
00387         ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
00388 
00389         
00390         LightControl *lightControl = new LightControl();
00391 
00392         ros::AsyncSpinner spinner(1);
00393         spinner.start();
00394 
00395         while (!gShutdownRequest)
00396         {
00397                 ros::WallDuration(0.05).sleep();
00398         }
00399 
00400         delete lightControl;
00401 
00402         ros::shutdown();
00403 
00404         return 0;
00405 }