#include <dashel/dashel.h>
#include <boost/thread.hpp>
#include <boost/thread/mutex.hpp>
#include <aseba/msg/msg.h>
#include <aseba/msg/descriptions-manager.h>
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "asebaros/LoadScripts.h"
#include "asebaros/GetNodeList.h"
#include "asebaros/GetNodeId.h"
#include "asebaros/GetNodeName.h"
#include "asebaros/GetVariableList.h"
#include "asebaros/SetVariable.h"
#include "asebaros/GetVariable.h"
#include "asebaros/GetEventId.h"
#include "asebaros/GetEventName.h"
#include "asebaros/AsebaEvent.h"
#include "asebaros/AsebaAnonymousEvent.h"
#include <vector>
Go to the source code of this file.
Classes | |
class | AsebaDashelHub |
class | AsebaROS |
class | AsebaROS::GetVariableQueryKey |
struct | AsebaROS::GetVariableQueryValue |
Typedefs | |
typedef std::vector < ros::Publisher > | Publishers |
typedef std::vector < ros::ServiceServer > | ServiceServers |
typedef std::vector < ros::Subscriber > | Subscribers |
typedef std::vector<ros::Publisher> Publishers |
Definition at line 69 of file asebaros.h.
typedef std::vector<ros::ServiceServer> ServiceServers |
Definition at line 68 of file asebaros.h.
typedef std::vector<ros::Subscriber> Subscribers |
Definition at line 70 of file asebaros.h.