00001 00023 #ifndef TESTSCDSPSO_H_ 00024 #define TESTSCDSPSO_H_ 00025 00026 #include "std_msgs/String.h" 00027 #include "nav_msgs/Odometry.h" 00028 #include "geometry_msgs/Twist.h" 00029 00030 #include "micros_swarm/scds_pso.h" 00031 #include "micros_swarm/micros_swarm.h" 00032 00033 namespace testscdspso{ 00034 00035 class TestSCDSPSO : public micros_swarm::Application 00036 { 00037 public: 00038 ros::Timer timer; 00039 ros::Publisher pub; 00040 ros::Subscriber sub; 00041 00042 micros_swarm::Agent agent; 00043 micros_swarm::SCDSPSOTuple tuple; 00044 void loop(const ros::TimerEvent&); 00045 void baseCallback(const nav_msgs::Odometry& lmsg); 00046 00047 float fitness(const std::vector<float>& vec); 00048 00049 TestSCDSPSO(); 00050 ~TestSCDSPSO(); 00051 virtual void init(); 00052 virtual void start(); 00053 virtual void stop(); 00054 }; 00055 }; 00056 00057 #endif