Public Member Functions | Private Member Functions | Private Attributes
micros_swarm::Agent Class Reference

#include <scds_pso.h>

List of all members.

Public Member Functions

 Agent ()
 Agent (std::string name)
void init_pos (const std::vector< float > &pos)
void init_vel (const std::vector< float > &vel)
void rand_init ()
void set_dim (int dim)
void set_fitness (const boost::function< float(const std::vector< float > &)> &fitness)
void set_max_pos (const std::vector< float > &pos)
void set_max_vel (const std::vector< float > &pos)
void set_min_pos (const std::vector< float > &pos)
void set_min_vel (const std::vector< float > &pos)
void set_param (float w, float c1, float c2)
void start ()
void start (int loop_gen)
void stop ()
 ~Agent ()

Private Member Functions

bool has_pos_limit (int index)
bool has_vel_limit (int index)
void loop (const ros::TimerEvent &)

Private Attributes

SCDSPSOTuple best_tuple_
float c1_
float c2_
int cur_gen_
std::vector< float > cur_pos_
std::vector< float > cur_vel_
int dim_
std::ofstream file
boost::function< float(const
std::vector< float > &)> 
fitness_
SCDSPSODataTuple gbest_
int gen_limit_
std::vector< float > max_pos_
std::vector< float > max_vel_
std::vector< float > min_pos_
std::vector< float > min_vel_
std::string name_
ros::NodeHandle nh_
SCDSPSODataTuple pbest_
int robot_id_
boost::shared_ptr< RuntimeHandlerth_
bool run_
ros::Timer timer_
float w_

Detailed Description

Definition at line 37 of file scds_pso.h.


Constructor & Destructor Documentation

Definition at line 27 of file scds_pso.cpp.

micros_swarm::Agent::Agent ( std::string  name)

Definition at line 43 of file scds_pso.cpp.

Definition at line 59 of file scds_pso.cpp.


Member Function Documentation

bool micros_swarm::Agent::has_pos_limit ( int  index) [private]

Definition at line 161 of file scds_pso.cpp.

bool micros_swarm::Agent::has_vel_limit ( int  index) [private]

Definition at line 169 of file scds_pso.cpp.

void micros_swarm::Agent::init_pos ( const std::vector< float > &  pos)

Definition at line 133 of file scds_pso.cpp.

void micros_swarm::Agent::init_vel ( const std::vector< float > &  vel)

Definition at line 154 of file scds_pso.cpp.

void micros_swarm::Agent::loop ( const ros::TimerEvent ) [private]

Definition at line 209 of file scds_pso.cpp.

Definition at line 177 of file scds_pso.cpp.

void micros_swarm::Agent::set_dim ( int  dim)

Definition at line 71 of file scds_pso.cpp.

void micros_swarm::Agent::set_fitness ( const boost::function< float(const std::vector< float > &)> &  fitness)

Definition at line 100 of file scds_pso.cpp.

void micros_swarm::Agent::set_max_pos ( const std::vector< float > &  pos)

Definition at line 112 of file scds_pso.cpp.

void micros_swarm::Agent::set_max_vel ( const std::vector< float > &  pos)

Definition at line 126 of file scds_pso.cpp.

void micros_swarm::Agent::set_min_pos ( const std::vector< float > &  pos)

Definition at line 105 of file scds_pso.cpp.

void micros_swarm::Agent::set_min_vel ( const std::vector< float > &  pos)

Definition at line 119 of file scds_pso.cpp.

void micros_swarm::Agent::set_param ( float  w,
float  c1,
float  c2 
)

Definition at line 64 of file scds_pso.cpp.

Definition at line 281 of file scds_pso.cpp.

void micros_swarm::Agent::start ( int  loop_gen)

Definition at line 297 of file scds_pso.cpp.

Definition at line 303 of file scds_pso.cpp.


Member Data Documentation

Definition at line 78 of file scds_pso.h.

float micros_swarm::Agent::c1_ [private]

Definition at line 65 of file scds_pso.h.

float micros_swarm::Agent::c2_ [private]

Definition at line 66 of file scds_pso.h.

Definition at line 74 of file scds_pso.h.

std::vector<float> micros_swarm::Agent::cur_pos_ [private]

Definition at line 72 of file scds_pso.h.

std::vector<float> micros_swarm::Agent::cur_vel_ [private]

Definition at line 73 of file scds_pso.h.

Definition at line 63 of file scds_pso.h.

std::ofstream micros_swarm::Agent::file [private]

Definition at line 86 of file scds_pso.h.

boost::function<float(const std::vector<float>& )> micros_swarm::Agent::fitness_ [private]

Definition at line 67 of file scds_pso.h.

Definition at line 77 of file scds_pso.h.

Definition at line 75 of file scds_pso.h.

std::vector<float> micros_swarm::Agent::max_pos_ [private]

Definition at line 69 of file scds_pso.h.

std::vector<float> micros_swarm::Agent::max_vel_ [private]

Definition at line 71 of file scds_pso.h.

std::vector<float> micros_swarm::Agent::min_pos_ [private]

Definition at line 68 of file scds_pso.h.

std::vector<float> micros_swarm::Agent::min_vel_ [private]

Definition at line 70 of file scds_pso.h.

std::string micros_swarm::Agent::name_ [private]

Definition at line 61 of file scds_pso.h.

Definition at line 83 of file scds_pso.h.

Definition at line 76 of file scds_pso.h.

Definition at line 80 of file scds_pso.h.

boost::shared_ptr<RuntimeHandle> micros_swarm::Agent::rth_ [private]

Definition at line 81 of file scds_pso.h.

bool micros_swarm::Agent::run_ [private]

Definition at line 62 of file scds_pso.h.

Definition at line 84 of file scds_pso.h.

float micros_swarm::Agent::w_ [private]

Definition at line 64 of file scds_pso.h.


The documentation for this class was generated from the following files:


micros_swarm
Author(s):
autogenerated on Thu Jun 6 2019 18:52:14