00001 #include "asebaros.h"
00002
00003 #include <aseba/compiler/compiler.h>
00004
00005 #include <ros/console.h>
00006
00007 #include <vector>
00008 #include <sstream>
00009 #include <boost/format.hpp>
00010
00011 #include <libxml/parser.h>
00012 #include <libxml/tree.h>
00013
00014
00015 using namespace asebaros;
00016 using namespace std;
00017 using namespace boost;
00018 using namespace Dashel;
00019 using namespace Aseba;
00020
00021
00022
00023 AsebaDashelHub::AsebaDashelHub(AsebaROS* asebaROS, unsigned port, bool forward):
00024 Dashel::Hub(),
00025 asebaROS(asebaROS),
00026 forward(forward)
00027 {
00028 ostringstream oss;
00029 oss << "tcpin:port=" << port;
00030 Dashel::Hub::connect(oss.str());
00031 }
00032
00033 static string asebaMsgToString(Message *message)
00034 {
00035 ostringstream oss;
00036 message->dump(oss);
00037 return oss.str();
00038 }
00039
00040 void AsebaDashelHub::sendMessage(Message *message, bool doLock, Stream* sourceStream)
00041 {
00042
00043 ROS_DEBUG_STREAM("sending aseba message: " << asebaMsgToString(message));
00044
00045
00046 if (doLock)
00047 lock();
00048
00049
00050 for (StreamsSet::iterator it = dataStreams.begin(); it != dataStreams.end();++it)
00051 {
00052 Stream* destStream(*it);
00053
00054 if ((forward) && (destStream == sourceStream))
00055 continue;
00056
00057 try
00058 {
00059 message->serialize(destStream);
00060 destStream->flush();
00061 }
00062 catch (DashelException e)
00063 {
00064
00065 ROS_ERROR("error while writing message");
00066 }
00067 }
00068
00069 if (doLock)
00070 unlock();
00071 }
00072
00073 void AsebaDashelHub::operator()()
00074 {
00075 Hub::run();
00076
00077 ros::shutdown();
00078 }
00079
00080 void AsebaDashelHub::startThread()
00081 {
00082 thread = new boost::thread(ref(*this));
00083 }
00084
00085 void AsebaDashelHub::stopThread()
00086 {
00087 Hub::stop();
00088 thread->join();
00089 delete thread;
00090 thread = 0;
00091 }
00092
00093
00094
00095 void AsebaDashelHub::incomingData(Stream *stream)
00096 {
00097
00098 Message *message = 0;
00099 try
00100 {
00101 message = Message::receive(stream);
00102 }
00103 catch (DashelException e)
00104 {
00105
00106 ROS_ERROR("error while writing message");
00107 }
00108
00109
00110 sendMessage(message, false, stream);
00111
00112
00113 asebaROS->processAsebaMessage(message);
00114
00115
00116 delete message;
00117 }
00118
00119 void AsebaDashelHub::connectionCreated(Stream *stream)
00120 {
00121 ROS_INFO_STREAM("Incoming connection from " << stream->getTargetName());
00122
00123 if (dataStreams.size() == 1)
00124 {
00125
00126
00127
00128 GetDescription getDescription;
00129 sendMessage(&getDescription, false);
00130 }
00131 }
00132
00133 void AsebaDashelHub::connectionClosed(Stream* stream, bool abnormal)
00134 {
00135 if (abnormal)
00136 ROS_INFO_STREAM("Abnormal connection closed to " << stream->getTargetName() << " : " << stream->getFailReason());
00137 else
00138 ROS_INFO_STREAM("Normal connection closed to " << stream->getTargetName());
00139 }
00140
00141
00142
00143
00144 bool AsebaROS::loadScript(LoadScripts::Request& req, LoadScripts::Response& res)
00145 {
00146
00147
00148
00149 const string& fileName(req.fileName);
00150 xmlDoc *doc = xmlReadFile(fileName.c_str(), NULL, 0);
00151 if (!doc)
00152 {
00153 ROS_ERROR_STREAM("Cannot read XML from file " << fileName);
00154 return false;
00155 }
00156 xmlNode *domRoot = xmlDocGetRootElement(doc);
00157
00158
00159 mutex.lock();
00160 commonDefinitions.events.clear();
00161 commonDefinitions.constants.clear();
00162 userDefinedVariablesMap.clear();
00163 pubs.clear();
00164 subs.clear();
00165 mutex.unlock();
00166
00167
00168 int noNodeCount = 0;
00169 bool wasError = false;
00170 if (!xmlStrEqual(domRoot->name, BAD_CAST("network")))
00171 {
00172 ROS_ERROR("root node is not \"network\", XML considered as invalid");
00173 wasError = true;
00174 }
00175 else for (xmlNode *domNode = xmlFirstElementChild(domRoot); domNode; domNode = domNode->next)
00176 {
00177
00178 if (domNode->type == XML_ELEMENT_NODE)
00179 {
00180 if (xmlStrEqual(domNode->name, BAD_CAST("node")))
00181 {
00182
00183 xmlChar *name = xmlGetProp(domNode, BAD_CAST("name"));
00184 if (!name)
00185 ROS_WARN("missing \"name\" attribute in \"node\" entry");
00186 else
00187 {
00188 const string _name((const char *)name);
00189 xmlChar * text = xmlNodeGetContent(domNode);
00190 if (!text)
00191 ROS_WARN("missing text in \"node\" entry");
00192 else
00193 {
00194
00195 mutex.lock();
00196 bool ok;
00197 unsigned nodeId(DescriptionsManager::getNodeId(_name, &ok));
00198 mutex.unlock();
00199 if (ok)
00200 {
00201 mutex.lock();
00202
00203 std::istringstream is((const char *)text);
00204 Error error;
00205 BytecodeVector bytecode;
00206 unsigned allocatedVariablesCount;
00207
00208 Compiler compiler;
00209 compiler.setTargetDescription(getDescription(nodeId));
00210 compiler.setCommonDefinitions(&commonDefinitions);
00211 bool result = compiler.compile(is, bytecode, allocatedVariablesCount, error);
00212 mutex.unlock();
00213
00214 if (result)
00215 {
00216 typedef std::vector<Message*> MessageVector;
00217 MessageVector messages;
00218 sendBytecode(messages, nodeId, std::vector<uint16>(bytecode.begin(), bytecode.end()));
00219 for (MessageVector::const_iterator it = messages.begin(); it != messages.end(); ++it)
00220 {
00221 hub.sendMessage(*it, true);
00222 delete *it;
00223 }
00224 Run msg(nodeId);
00225 hub.sendMessage(&msg, true);
00226
00227 mutex.lock();
00228 userDefinedVariablesMap[_name] = *compiler.getVariablesMap();
00229 mutex.unlock();
00230 }
00231 else
00232 {
00233 ROS_ERROR_STREAM("compilation of " << fileName << ", node " << _name << " failed: " << error.toString());
00234 wasError = true;
00235 }
00236 }
00237 else
00238 noNodeCount++;
00239
00240
00241 xmlFree(text);
00242 }
00243 xmlFree(name);
00244 }
00245 }
00246 else if (xmlStrEqual(domNode->name, BAD_CAST("event")))
00247 {
00248
00249 xmlChar *name = xmlGetProp(domNode, BAD_CAST("name"));
00250 if (!name)
00251 ROS_WARN("missing \"name\" attribute in \"event\" entry");
00252 xmlChar *size = xmlGetProp(domNode, BAD_CAST("size"));
00253 if (!size)
00254 ROS_WARN("missing \"size\" attribute in \"event\" entry");
00255
00256 if (name && size)
00257 {
00258 int eventSize(atoi((const char *)size));
00259 if (eventSize > ASEBA_MAX_EVENT_ARG_SIZE)
00260 {
00261 ROS_ERROR("Event %s has a length %d larger than maximum %d", name, eventSize, ASEBA_MAX_EVENT_ARG_SIZE);
00262 wasError = true;
00263 break;
00264 }
00265 else
00266 {
00267 lock_guard<boost::mutex> lock(mutex);
00268 commonDefinitions.events.push_back(NamedValue(string((const char *)name), eventSize));
00269 }
00270 }
00271
00272 if (name)
00273 xmlFree(name);
00274 if (size)
00275 xmlFree(size);
00276 }
00277 else if (xmlStrEqual(domNode->name, BAD_CAST("constant")))
00278 {
00279
00280 xmlChar *name = xmlGetProp(domNode, BAD_CAST("name"));
00281 if (!name)
00282 ROS_WARN("missing \"name\" attribute in \"constant\" entry");
00283 xmlChar *value = xmlGetProp(domNode, BAD_CAST("value"));
00284 if (!value)
00285 ROS_WARN("missing \"value\" attribute in \"constant\" entry");
00286
00287 if (name && value)
00288 {
00289 lock_guard<boost::mutex> lock(mutex);
00290 commonDefinitions.constants.push_back(NamedValue(string((const char *)name), atoi((const char *)value)));
00291 }
00292
00293 if (name)
00294 xmlFree(name);
00295 if (value)
00296 xmlFree(value);
00297 }
00298 else
00299 ROS_WARN_STREAM("Unknown XML node seen in .aesl file: " << domNode->name);
00300 }
00301 }
00302
00303
00304 xmlFreeDoc(doc);
00305
00306
00307 if (wasError)
00308 {
00309 ROS_ERROR_STREAM("There was an error while loading script " << fileName);
00310 mutex.lock();
00311 commonDefinitions.events.clear();
00312 commonDefinitions.constants.clear();
00313 userDefinedVariablesMap.clear();
00314 mutex.unlock();
00315 }
00316
00317
00318 if (noNodeCount)
00319 {
00320 ROS_WARN_STREAM(noNodeCount << " scripts have no corresponding nodes in the current network and have not been loaded.");
00321 }
00322
00323
00324 mutex.lock();
00325 typedef EventsDescriptionsVector::const_iterator EventsDescriptionsConstIt;
00326 for (size_t i = 0; i < commonDefinitions.events.size(); ++i)
00327 {
00328 const string& name(commonDefinitions.events[i].name);
00329 pubs.push_back(n.advertise<AsebaEvent>("events/"+name, 100));
00330 subs.push_back(n.subscribe<AsebaEvent>("events/"+name, 100, bind(&AsebaROS::knownEventReceived, this, i, _1)));
00331 }
00332 mutex.unlock();
00333
00334 return true;
00335 }
00336
00337 bool AsebaROS::getNodeList(GetNodeList::Request& req, GetNodeList::Response& res)
00338 {
00339 lock_guard<boost::mutex> lock(mutex);
00340
00341 transform(nodesNames.begin(), nodesNames.end(), back_inserter(res.nodeList), bind(&NodesNamesMap::value_type::first,_1));
00342 return true;
00343 }
00344
00345 bool AsebaROS::getNodeId(GetNodeId::Request& req, GetNodeId::Response& res)
00346 {
00347 lock_guard<boost::mutex> lock(mutex);
00348
00349 NodesNamesMap::const_iterator nodeIt(nodesNames.find(req.nodeName));
00350 if (nodeIt != nodesNames.end())
00351 {
00352 res.nodeId = nodeIt->second;
00353 return true;
00354 }
00355 else
00356 {
00357 ROS_ERROR_STREAM("node " << req.nodeName << " does not exists");
00358 return false;
00359 }
00360 }
00361
00362 bool AsebaROS::getNodeName(GetNodeName::Request& req, GetNodeName::Response& res)
00363 {
00364 lock_guard<boost::mutex> lock(mutex);
00365
00366 NodesDescriptionsMap::const_iterator nodeIt(nodesDescriptions.find(req.nodeId));
00367 if (nodeIt != nodesDescriptions.end())
00368 {
00369 res.nodeName = nodeIt->second.name;
00370 return true;
00371 }
00372 else
00373 {
00374 ROS_ERROR_STREAM("node " << req.nodeId << " does not exists");
00375 return false;
00376 }
00377 }
00378
00379 struct ExtractName
00380 {
00381 string operator()(const TargetDescription::NamedVariable& nv) const { return nv.name; }
00382 };
00383
00384 bool AsebaROS::getVariableList(GetVariableList::Request& req, GetVariableList::Response& res)
00385 {
00386 lock_guard<boost::mutex> lock(mutex);
00387
00388 NodesNamesMap::const_iterator nodeIt(nodesNames.find(req.nodeName));
00389 if (nodeIt != nodesNames.end())
00390 {
00391
00392 const UserDefinedVariablesMap::const_iterator userVarMapIt(userDefinedVariablesMap.find(req.nodeName));
00393 if (userVarMapIt != userDefinedVariablesMap.end())
00394 {
00395
00396 const Compiler::VariablesMap& variablesMap(userVarMapIt->second);
00397 transform(variablesMap.begin(), variablesMap.end(),
00398 back_inserter(res.variableList), bind(&Compiler::VariablesMap::value_type::first,_1));
00399 }
00400 else
00401 {
00402
00403 const unsigned nodeId(nodeIt->second);
00404 const NodesDescriptionsMap::const_iterator descIt(nodesDescriptions.find(nodeId));
00405 const NodeDescription& description(descIt->second);
00406 transform(description.namedVariables.begin(), description.namedVariables.end(),
00407 back_inserter(res.variableList), ExtractName());
00408 }
00409 return true;
00410 }
00411 else
00412 {
00413 ROS_ERROR_STREAM("node " << req.nodeName << " does not exists");
00414 return false;
00415 }
00416 }
00417
00418
00419
00420 bool AsebaROS::setVariable(SetVariable::Request& req, SetVariable::Response& res)
00421 {
00422
00423 unsigned nodeId, pos;
00424
00425 mutex.lock();
00426 bool exists = getNodePosFromNames(req.nodeName, req.variableName, nodeId, pos);
00427 mutex.unlock();
00428
00429 if (!exists)
00430 return false;
00431
00432 SetVariables msg(nodeId, pos, req.data);
00433 hub.sendMessage(&msg, true);
00434 return true;
00435 }
00436
00437 bool AsebaROS::getVariable(GetVariable::Request& req, GetVariable::Response& res)
00438 {
00439 unsigned nodeId, pos;
00440
00441
00442 unique_lock<boost::mutex> lock(mutex);
00443
00444
00445 bool exists = getNodePosFromNames(req.nodeName, req.variableName, nodeId, pos);
00446 if (!exists)
00447 return false;
00448 bool ok;
00449 unsigned length = getVariableSize(nodeId, req.variableName, &ok);
00450 if (!ok)
00451 return false;
00452
00453
00454 const GetVariableQueryKey key(nodeId, pos);
00455 GetVariableQueryValue query;
00456 getVariableQueries[key] = &query;
00457 lock.unlock();
00458
00459
00460 GetVariables msg(nodeId, pos, length);
00461 hub.sendMessage(&msg, true);
00462 system_time const timeout(get_system_time()+posix_time::milliseconds(100));
00463
00464
00465 bool result;
00466 lock.lock();
00467 while (query.data.empty())
00468 {
00469 result = query.cond.timed_wait(lock, timeout);
00470 if (!result)
00471 break;
00472 }
00473
00474
00475 getVariableQueries.erase(key);
00476 if (result)
00477 {
00478 res.data = query.data;
00479 return true;
00480 }
00481 else
00482 {
00483 ROS_ERROR_STREAM("read of node " << req.nodeName << ", variable " << req.variableName << " did not return a valid answer within 100ms");
00484 return false;
00485 }
00486 }
00487
00488 bool AsebaROS::getEventId(GetEventId::Request& req, GetEventId::Response& res)
00489 {
00490
00491 lock_guard<boost::mutex> lock(mutex);
00492 size_t id;
00493 if (commonDefinitions.events.contains(req.name, &id))
00494 {
00495 res.id = id;
00496 return true;
00497 }
00498 return false;
00499 }
00500
00501 bool AsebaROS::getEventName(GetEventName::Request& req, GetEventName::Response& res)
00502 {
00503
00504 lock_guard<boost::mutex> lock(mutex);
00505 if (req.id < commonDefinitions.events.size())
00506 {
00507 res.name = commonDefinitions.events[req.id].name;
00508 return true;
00509 }
00510 return false;
00511 }
00512
00513 bool AsebaROS::getNodePosFromNames(const string& nodeName, const string& variableName, unsigned& nodeId, unsigned& pos) const
00514 {
00515
00516
00517
00518 NodesNamesMap::const_iterator nodeIt(nodesNames.find(nodeName));
00519 if (nodeIt == nodesNames.end())
00520 {
00521 ROS_ERROR_STREAM("node " << nodeName << " does not exists");
00522 return false;
00523 }
00524 nodeId = nodeIt->second;
00525 pos = unsigned(-1);
00526
00527
00528 const UserDefinedVariablesMap::const_iterator userVarMapIt(userDefinedVariablesMap.find(nodeName));
00529 if (userVarMapIt != userDefinedVariablesMap.end())
00530 {
00531 const Compiler::VariablesMap& userVarMap(userVarMapIt->second);
00532 const Compiler::VariablesMap::const_iterator userVarIt(userVarMap.find(variableName));
00533 if (userVarIt != userVarMap.end())
00534 {
00535 pos = userVarIt->second.first;
00536 }
00537 }
00538
00539
00540 if (pos == unsigned(-1))
00541 {
00542 bool ok;
00543 pos = getVariablePos(nodeId, variableName, &ok);
00544 if (!ok)
00545 {
00546 ROS_ERROR_STREAM("variable " << variableName << " does not exists in node " << nodeName);
00547 return false;
00548 }
00549 }
00550 return true;
00551 }
00552
00553 void AsebaROS::sendEventOnROS(const UserMessage* asebaMessage)
00554 {
00555
00556 assert(pubs.size() == commonDefinitions.events.size());
00557 if (asebaMessage->type < commonDefinitions.events.size())
00558 {
00559
00560 shared_ptr<AsebaEvent> event(new AsebaEvent);
00561 event->stamp = ros::Time::now();
00562 event->source = asebaMessage->source;
00563 event->data = asebaMessage->data;
00564 pubs[asebaMessage->type].publish(event);
00565 }
00566 else
00567 {
00568
00569 shared_ptr<AsebaAnonymousEvent> event(new AsebaAnonymousEvent);
00570 event->stamp = ros::Time::now();
00571 event->source = asebaMessage->source;
00572 event->type = asebaMessage->type;
00573 event->data = asebaMessage->data;
00574 anonPub.publish(event);
00575 }
00576 }
00577
00578 void AsebaROS::nodeDescriptionReceived(unsigned nodeId)
00579 {
00580
00581 nodesNames[nodesDescriptions.at(nodeId).name] = nodeId;
00582 }
00583
00584 void AsebaROS::eventReceived(const AsebaAnonymousEventConstPtr& event)
00585 {
00586
00587 UserMessage userMessage(event->type, event->data);
00588 hub.sendMessage(&userMessage, true);
00589 }
00590
00591 void AsebaROS::knownEventReceived(const uint16 id, const AsebaEventConstPtr& event)
00592 {
00593
00594 UserMessage userMessage(id, event->data);
00595 hub.sendMessage(&userMessage, true);
00596 }
00597
00598 AsebaROS::AsebaROS(unsigned port, bool forward):
00599 n("aseba"),
00600 anonPub(n.advertise<AsebaAnonymousEvent>("anonymous_events", 100)),
00601 anonSub(n.subscribe("anonymous_events", 100, &AsebaROS::eventReceived, this)),
00602 hub(this, port, forward)
00603 {
00604
00605
00606
00607 s.push_back(n.advertiseService("load_script", &AsebaROS::loadScript, this));
00608
00609
00610 s.push_back(n.advertiseService("get_node_list", &AsebaROS::getNodeList, this));
00611 s.push_back(n.advertiseService("get_node_id", &AsebaROS::getNodeId, this));
00612 s.push_back(n.advertiseService("get_node_name", &AsebaROS::getNodeName, this));
00613
00614
00615 s.push_back(n.advertiseService("get_variable_list", &AsebaROS::getVariableList, this));
00616 s.push_back(n.advertiseService("set_variable", &AsebaROS::setVariable, this));
00617 s.push_back(n.advertiseService("get_variable", &AsebaROS::getVariable, this));
00618
00619
00620 s.push_back(n.advertiseService("get_event_id", &AsebaROS::getEventId, this));
00621 s.push_back(n.advertiseService("get_event_name", &AsebaROS::getEventName, this));
00622 }
00623
00624 AsebaROS::~AsebaROS()
00625 {
00626
00627 xmlCleanupParser();
00628 }
00629
00630 void AsebaROS::run()
00631 {
00632
00633 hub.startThread();
00634 ros::spin();
00635
00636 hub.stopThread();
00637 }
00638
00639 void AsebaROS::processAsebaMessage(Message *message)
00640 {
00641
00642 lock_guard<boost::mutex> lock(mutex);
00643
00644
00645 DescriptionsManager::processMessage(message);
00646
00647
00648 UserMessage *userMessage = dynamic_cast<UserMessage *>(message);
00649 if (userMessage)
00650 sendEventOnROS(userMessage);
00651
00652
00653 Variables *variables = dynamic_cast<Variables *>(message);
00654 if (variables)
00655 {
00656 const GetVariableQueryKey queryKey(variables->source, variables->start);
00657 GetVariableQueryMap::const_iterator queryIt(getVariableQueries.find(queryKey));
00658 if (queryIt != getVariableQueries.end())
00659 {
00660 queryIt->second->data = variables->variables;
00661 queryIt->second->cond.notify_one();
00662 }
00663 else
00664 ROS_WARN_STREAM("received Variables from node " << variables->source << ", pos " << variables->start << ", but no corresponding query was found");
00665 }
00666 }
00667
00669 void dumpHelp(std::ostream &stream, const char *programName)
00670 {
00671 stream << "AsebaROS, connects aseba components together and with ROS, usage:\n";
00672 stream << programName << " [options] [additional targets]*\n";
00673 stream << "Options:\n";
00674 stream << "-l, --loop : makes the switch transmit messages back to the send, not only forward them.\n";
00675 stream << "-p port : listens to incoming connection on this port\n";
00676 stream << "-h, --help : shows this help\n";
00677 stream << "ROS_OPTIONS : see ROS documentation\n";
00678 stream << "Additional targets are any valid Dashel targets." << std::endl;
00679 }
00680
00681 int main(int argc, char *argv[])
00682 {
00683 ros::init(argc, argv, "aseba");
00684
00685 unsigned port = ASEBA_DEFAULT_PORT;
00686 bool forward = true;
00687 std::vector<std::string> additionalTargets;
00688
00689 int argCounter = 1;
00690
00691 while (argCounter < argc)
00692 {
00693 const char *arg = argv[argCounter];
00694
00695 if ((strcmp(arg, "-l") == 0) || (strcmp(arg, "--loop") == 0))
00696 {
00697 forward = false;
00698 }
00699 else if (strcmp(arg, "-p") == 0)
00700 {
00701 arg = argv[++argCounter];
00702 port = atoi(arg);
00703 }
00704 else if ((strcmp(arg, "-h") == 0) || (strcmp(arg, "--help") == 0))
00705 {
00706 dumpHelp(std::cout, argv[0]);
00707 return 0;
00708 }
00709 else
00710 {
00711 additionalTargets.push_back(argv[argCounter]);
00712 }
00713 argCounter++;
00714 }
00715
00716 AsebaROS asebaROS(port, forward);
00717
00718 try
00719 {
00720 for (size_t i = 0; i < additionalTargets.size(); i++)
00721 asebaROS.connectTarget(additionalTargets[i]);
00722 }
00723 catch(Dashel::DashelException e)
00724 {
00725 std::cerr << e.what() << std::endl;
00726 }
00727
00728 asebaROS.run();
00729
00730 return 0;
00731 }
00732
00733
00734