Go to the documentation of this file.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 #ifndef __JAUS_MOBILITY_LOCAL_WAYPOINT_LIST_DRIVER__H
00042 #define __JAUS_MOBILITY_LOCAL_WAYPOINT_LIST_DRIVER__H
00043
00044 #include "jaus/mobility/drivers/listdriver.h"
00045 #include "jaus/mobility/drivers/localwaypointdriver.h"
00046
00047 namespace JAUS
00048 {
00059 class JAUS_MOBILITY_DLL LocalWaypointListDriver : public ListDriver
00060 {
00061 public:
00062 const static std::string Name;
00063 LocalWaypointListDriver();
00064 virtual ~LocalWaypointListDriver();
00065
00066 virtual void ExecuteList(const double speedMetersPerSecond);
00067
00068 virtual bool IsElementSupported(const Message* message) const;
00069
00070 virtual void Receive(const Message* message);
00071
00072 virtual Message* CreateMessage(const UShort messageCode) const;
00073
00074 virtual bool GenerateEvent(const Events::Subscription& info) const;
00075
00076 virtual bool IsEventSupported(const Events::Type type,
00077 const double requestedPeriodicRate,
00078 const Message* queryMessage,
00079 double& confirmedPeriodicRate,
00080 std::string& errorMessage) const;
00081
00082 JAUS::SetLocalWaypoint GetCurrentWaypoint() const;
00083
00084 std::vector<JAUS::SetLocalWaypoint> GetWaypointList() const;
00085
00086 virtual void PrintStatus() const;
00087 };
00088 }
00089
00090 #endif
00091