message_manager.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *       * Redistributions of source code must retain the above copyright
00011  *       notice, this list of conditions and the following disclaimer.
00012  *       * Redistributions in binary form must reproduce the above copyright
00013  *       notice, this list of conditions and the following disclaimer in the
00014  *       documentation and/or other materials provided with the distribution.
00015  *       * Neither the name of the Southwest Research Institute, nor the names
00016  *       of its contributors may be used to endorse or promote products derived
00017  *       from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 #ifdef ROS
00032 #include "ros/ros.h"
00033 #include "simple_message/message_manager.h"
00034 #include "simple_message/log_wrapper.h"
00035 #include "simple_message/simple_message.h"
00036 #endif
00037 
00038 #ifdef MOTOPLUS
00039 #include "message_manager.h"
00040 #include "log_wrapper.h"
00041 #include "simple_message.h"
00042 #endif
00043 
00044 
00045 using namespace industrial::smpl_msg_connection;
00046 using namespace industrial::message_handler;
00047 using namespace industrial::simple_message;
00048 using namespace industrial::comms_fault_handler;
00049 using namespace industrial::simple_comms_fault_handler;
00050 
00051 namespace industrial
00052 {
00053 namespace message_manager
00054 {
00055 
00059 MessageManager::MessageManager()
00060 {
00061   this->num_handlers_ = 0;
00062   for (unsigned int i = 0; i < this->getMaxNumHandlers(); i++)
00063   {
00064     this->handlers_[i] = NULL;
00065   }
00066   this->comms_hndlr_ = NULL;
00067 }
00068 
00069 MessageManager::~MessageManager()
00070 {
00071 
00072 }
00073 
00074 bool MessageManager::init(SmplMsgConnection* connection)
00075 {
00076   bool rtn = false;
00077 
00078   LOG_INFO("Initializing message manager with default comms fault handler");
00079 
00080 
00081   if (NULL != connection)
00082   {
00083     this->getDefaultCommsFaultHandler().init(connection);
00084     this->init(connection, (CommsFaultHandler*)(&this->getDefaultCommsFaultHandler()));
00085     rtn = true;
00086   }
00087   else
00088   {
00089     LOG_ERROR("NULL connection passed into manager init");
00090     rtn = false;
00091   }
00092 
00093   return rtn;
00094 }
00095 
00096 bool MessageManager::init(SmplMsgConnection* connection, CommsFaultHandler* fault_handler)
00097 {
00098   bool rtn = false;
00099 
00100     LOG_INFO("Initializing message manager");
00101 
00102     if (NULL != connection && NULL != fault_handler)
00103     {
00104       this->setConnection(connection);
00105       this->getPingHandler().init(connection);
00106       this->setCommsFaultHandler(fault_handler);
00107 
00108       if (this->add(&this->getPingHandler()))
00109       {
00110         rtn = true;
00111       }
00112       else
00113       {
00114         rtn = false;
00115         LOG_WARN("Failed to add ping handler, manager won't respond to pings");
00116       }
00117 
00118     }
00119     else
00120     {
00121       LOG_ERROR("NULL connection or NULL fault handler passed into manager init");
00122       rtn = false;
00123     }
00124 
00125     return rtn;
00126   }
00127 
00128 
00129 
00130 void MessageManager::spinOnce()
00131 {
00132   SimpleMessage msg;
00133   MessageHandler* handler = NULL;
00134 
00135   if(!this->getConnection()->isConnected())
00136   {
00137     this->getCommsFaultHandler()->connectionFailCB();
00138   }
00139 
00140   if (this->getConnection()->receiveMsg(msg))
00141   {
00142     LOG_COMM("Message received");
00143     handler = this->getHandler(msg.getMessageType());
00144 
00145     if (NULL != handler)
00146     {
00147       LOG_DEBUG("Executing handler callback for message type: %d", handler->getMsgType());
00148       handler->callback(msg);
00149     }
00150     else
00151     {
00152       if (CommTypes::SERVICE_REQUEST == msg.getCommType())
00153       {
00154         simple_message::SimpleMessage fail;
00155         fail.init(msg.getMessageType(), CommTypes::SERVICE_REPLY, ReplyTypes::FAILURE);
00156         this->getConnection()->sendMsg(fail);
00157         LOG_WARN("Unhandled message type encounters, sending failure reply");
00158       }
00159       LOG_ERROR("Message callback for message type: %d, not executed", msg.getMessageType());
00160     }
00161   }
00162   else
00163   {
00164     LOG_ERROR("Failed to receive incoming message");
00165     this->getCommsFaultHandler()->sendFailCB();
00166   }
00167 }
00168 
00169 int ms_per_clock;
00170 void mySleep(int sec)
00171 {
00172 #ifdef MOTOPLUS
00173   if (ms_per_clock <= 0)
00174     ms_per_clock = mpGetRtc();
00175 
00176   mpTaskDelay(sec * 1000 / ms_per_clock);
00177 #else
00178   sleep(sec);
00179 #endif
00180 }
00181 
00182 void MessageManager::spin()
00183 {
00184   LOG_INFO("Entering message manager spin loop");
00185 #ifdef ROS
00186   while (ros::ok())
00187 #else
00188   while (true)
00189 #endif
00190   {
00191     this->spinOnce();
00192 
00193     // Throttle loop speed if waiting for a re-connection
00194     if (!this->getConnection()->isConnected())
00195       mySleep(5);
00196   }
00197 }
00198 
00199 bool MessageManager::add(MessageHandler * handler, bool allow_replace)
00200 {
00201   int idx = -1;
00202   bool rtn = false;
00203 
00204   if (NULL != handler)
00205   {
00206     // If get handler returns -1 then a hander for the message type
00207     // does not exist, and a new one should be added
00208     idx = getHandlerIdx(handler->getMsgType());
00209     if (0 > idx)
00210     {
00211       if (this->getMaxNumHandlers() > this->getNumHandlers())
00212       {
00213         this->handlers_[this->getNumHandlers()] = handler;
00214         this->setNumHandlers(this->getNumHandlers() + 1);
00215         LOG_INFO("Added message handler for message type: %d", handler->getMsgType());
00216         rtn = true;
00217       }
00218       else
00219       {
00220         LOG_ERROR("Max number of handlers exceeded");
00221         rtn = false;
00222       }
00223     }
00224     else if (allow_replace)
00225     {
00226       this->handlers_[idx] = handler;
00227     }
00228     else
00229     {
00230       LOG_ERROR("Failed to add handler for: %d, handler already exists", handler->getMsgType());
00231       rtn = false;
00232     }
00233   }
00234   else
00235   {
00236     LOG_ERROR("NULL handler not added");
00237     rtn = false;
00238   }
00239   return rtn;
00240 }
00241 
00242 MessageHandler* MessageManager::getHandler(int msg_type)
00243 {
00244   int idx = getHandlerIdx(msg_type);
00245 
00246   if (idx < 0)
00247     return NULL;
00248   else
00249     return this->handlers_[idx];
00250 }
00251 
00252 int MessageManager::getHandlerIdx(int msg_type)
00253 {
00254   int rtn = -1;
00255   MessageHandler* temp = NULL;
00256 
00257   for (unsigned int i = 0; i < this->getMaxNumHandlers(); i++)
00258   {
00259     temp = this->handlers_[i];
00260     if (NULL == temp) break;  // end of handler-list
00261 
00262     if (temp->getMsgType() == msg_type)
00263     {
00264         rtn = i;
00265         break;
00266     }
00267   }
00268 
00269   return rtn;
00270 }
00271 
00272 } // namespace message_manager
00273 } // namespace industrial


simple_message
Author(s): Shaun Edwards
autogenerated on Mon Oct 6 2014 00:54:18