scds_pso.h
Go to the documentation of this file.
1 
23 #ifndef SCDS_PSO_H_
24 #define SCDS_PSO_H_
25 
26 #include <iostream>
27 #include <fstream>
28 #include <vector>
29 #include <set>
30 #include <boost/function.hpp>
31 #include <ros/ros.h>
32 
34 
35 namespace micros_swarm{
36 
37  class Agent{
38  public:
39  Agent();
40  Agent(std::string name);
41  ~Agent();
42  void set_param(float w, float c1, float c2);
43  void set_dim(int dim);
44  void set_fitness(const boost::function<float(const std::vector<float>& )>& fitness);
45  void set_min_pos(const std::vector<float>& pos);
46  void set_max_pos(const std::vector<float>& pos);
47  void set_min_vel(const std::vector<float>& pos);
48  void set_max_vel(const std::vector<float>& pos);
49  void init_pos(const std::vector<float>& pos);
50  void init_vel(const std::vector<float>& vel);
51  void rand_init();
52  void start();
53  void start(int loop_gen);
54  void stop();
55  private:
56  bool has_pos_limit(int index);
57  bool has_vel_limit(int index);
58 
59  void loop(const ros::TimerEvent&);
60 
61  std::string name_;
62  bool run_;
63  int dim_;
64  float w_;
65  float c1_;
66  float c2_;
67  boost::function<float(const std::vector<float>& )> fitness_;
68  std::vector<float> min_pos_;
69  std::vector<float> max_pos_;
70  std::vector<float> min_vel_;
71  std::vector<float> max_vel_;
72  std::vector<float> cur_pos_;
73  std::vector<float> cur_vel_;
74  int cur_gen_;
79 
80  int robot_id_;
82 
85 
86  std::ofstream file;
87  };
88 };
89 
90 #endif
SCDSPSOTuple best_tuple_
Definition: scds_pso.h:78
void set_max_vel(const std::vector< float > &pos)
Definition: scds_pso.cpp:126
void init_vel(const std::vector< float > &vel)
Definition: scds_pso.cpp:154
ros::Timer timer_
Definition: scds_pso.h:84
std::vector< float > cur_pos_
Definition: scds_pso.h:72
void set_dim(int dim)
Definition: scds_pso.cpp:71
void set_max_pos(const std::vector< float > &pos)
Definition: scds_pso.cpp:112
bool has_pos_limit(int index)
Definition: scds_pso.cpp:161
boost::function< float(const std::vector< float > &)> fitness_
Definition: scds_pso.h:67
ros::NodeHandle nh_
Definition: scds_pso.h:83
std::vector< float > min_pos_
Definition: scds_pso.h:68
std::ofstream file
Definition: scds_pso.h:86
bool has_vel_limit(int index)
Definition: scds_pso.cpp:169
std::string name_
Definition: scds_pso.h:61
void set_min_pos(const std::vector< float > &pos)
Definition: scds_pso.cpp:105
std::vector< float > min_vel_
Definition: scds_pso.h:70
void loop(const ros::TimerEvent &)
Definition: scds_pso.cpp:209
void init_pos(const std::vector< float > &pos)
Definition: scds_pso.cpp:133
void set_param(float w, float c1, float c2)
Definition: scds_pso.cpp:64
SCDSPSODataTuple gbest_
Definition: scds_pso.h:77
std::vector< float > max_vel_
Definition: scds_pso.h:71
std::vector< float > max_pos_
Definition: scds_pso.h:69
boost::shared_ptr< RuntimeHandle > rth_
Definition: scds_pso.h:81
void set_fitness(const boost::function< float(const std::vector< float > &)> &fitness)
Definition: scds_pso.cpp:100
void set_min_vel(const std::vector< float > &pos)
Definition: scds_pso.cpp:119
std::vector< float > cur_vel_
Definition: scds_pso.h:73
SCDSPSODataTuple pbest_
Definition: scds_pso.h:76


micros_swarm
Author(s):
autogenerated on Mon Jun 10 2019 14:02:06