Public Member Functions | Private Attributes
micros_mars_task_alloc::MotivationalBehavior< VS_MsgType > Class Template Reference

#include <motivational_behavior.h>

Inheritance diagram for micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void acquiescence_calc ()
void impatience_calc ()
void impatience_reset_calc ()
void inter_robot_comm_callback (const micros_mars_task_alloc::HeartbeatConstPtr &msg)
void intra_robot_comm_callback (const micros_mars_task_alloc::HeartbeatConstPtr &msg)
void main_logic_callback (const ros::TimerEvent &)
 MotivationalBehavior ()
virtual void onInit ()
void send_inter_heartbeat (bool heartbeat)
void send_intra_heartbeat (bool heartbeat)
void sensory_feedback_callback (const boost::shared_ptr< const VS_MsgType > &msg)
virtual ~MotivationalBehavior ()

Private Attributes

double acquiescence_
bool active_
double active_time_duration_
double activity_suppression_
int behavior_set_number_
double delta_fast_
double delta_slow_
std::string forward_topic_
vector< vector< bool > > heartbeat_
vector< int > heartbeat_count_
double impatience_
double impatience_reset_
std::string inter_robot_comm_topic_
std::string intra_robot_comm_topic_
ros::Timer main_periodic_timer_
int maximum_time_step_
double motivation_
ros::NodeHandle nh_
double one_cycle_
ros::Publisher pub_forward_
ros::Publisher pub_inter_heartbeat_
ros::Publisher pub_intra_heartbeat_
int robot_number_
double sensory_feedback_
bool sensory_feedback_exist_
double sensory_feedback_timestamp_
std::string sensory_feedback_topic_
ros::Subscriber sub_0_
ros::Subscriber sub_1_
ros::Subscriber sub_2_
int this_behavior_set_ID_
int this_robot_ID_
double threshold_

Detailed Description

template<typename VS_MsgType>
class micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >

Definition at line 28 of file motivational_behavior.h.


Constructor & Destructor Documentation

template<typename VS_MsgType >
micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::MotivationalBehavior ( ) [inline]

Definition at line 31 of file motivational_behavior.h.

template<typename VS_MsgType >
virtual micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::~MotivationalBehavior ( ) [inline, virtual]

Definition at line 33 of file motivational_behavior.h.


Member Function Documentation

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::acquiescence_calc ( ) [inline]

Definition at line 179 of file motivational_behavior.h.

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::impatience_calc ( ) [inline]

Definition at line 161 of file motivational_behavior.h.

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::impatience_reset_calc ( ) [inline]

Definition at line 132 of file motivational_behavior.h.

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::inter_robot_comm_callback ( const micros_mars_task_alloc::HeartbeatConstPtr &  msg) [inline]

Definition at line 112 of file motivational_behavior.h.

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::intra_robot_comm_callback ( const micros_mars_task_alloc::HeartbeatConstPtr &  msg) [inline]

Definition at line 123 of file motivational_behavior.h.

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::main_logic_callback ( const ros::TimerEvent ) [inline]

Definition at line 232 of file motivational_behavior.h.

template<typename VS_MsgType >
virtual void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::onInit ( ) [inline, virtual]

Implements nodelet::Nodelet.

Definition at line 34 of file motivational_behavior.h.

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::send_inter_heartbeat ( bool  heartbeat) [inline]

Definition at line 216 of file motivational_behavior.h.

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::send_intra_heartbeat ( bool  heartbeat) [inline]

Definition at line 224 of file motivational_behavior.h.

template<typename VS_MsgType >
void micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::sensory_feedback_callback ( const boost::shared_ptr< const VS_MsgType > &  msg) [inline]

Definition at line 104 of file motivational_behavior.h.


Member Data Documentation

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::acquiescence_ [private]

Definition at line 290 of file motivational_behavior.h.

template<typename VS_MsgType >
bool micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::active_ [private]

Definition at line 298 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::active_time_duration_ [private]

Definition at line 299 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::activity_suppression_ [private]

Definition at line 295 of file motivational_behavior.h.

template<typename VS_MsgType >
int micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::behavior_set_number_ [private]

Definition at line 278 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::delta_fast_ [private]

Definition at line 303 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::delta_slow_ [private]

Definition at line 302 of file motivational_behavior.h.

template<typename VS_MsgType >
std::string micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::forward_topic_ [private]

Definition at line 285 of file motivational_behavior.h.

template<typename VS_MsgType >
vector< vector<bool> > micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::heartbeat_ [private]

Definition at line 307 of file motivational_behavior.h.

template<typename VS_MsgType >
vector<int> micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::heartbeat_count_ [private]

Definition at line 306 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::impatience_ [private]

Definition at line 289 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::impatience_reset_ [private]

Definition at line 296 of file motivational_behavior.h.

template<typename VS_MsgType >
std::string micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::inter_robot_comm_topic_ [private]

Definition at line 283 of file motivational_behavior.h.

template<typename VS_MsgType >
std::string micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::intra_robot_comm_topic_ [private]

Definition at line 284 of file motivational_behavior.h.

template<typename VS_MsgType >
ros::Timer micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::main_periodic_timer_ [private]

Definition at line 268 of file motivational_behavior.h.

template<typename VS_MsgType >
int micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::maximum_time_step_ [private]

Definition at line 280 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::motivation_ [private]

Definition at line 288 of file motivational_behavior.h.

template<typename VS_MsgType >
ros::NodeHandle micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::nh_ [private]

Reimplemented from nodelet::Nodelet.

Definition at line 267 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::one_cycle_ [private]

Definition at line 300 of file motivational_behavior.h.

template<typename VS_MsgType >
ros::Publisher micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::pub_forward_ [private]

Definition at line 274 of file motivational_behavior.h.

template<typename VS_MsgType >
ros::Publisher micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::pub_inter_heartbeat_ [private]

Definition at line 273 of file motivational_behavior.h.

template<typename VS_MsgType >
ros::Publisher micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::pub_intra_heartbeat_ [private]

Definition at line 272 of file motivational_behavior.h.

template<typename VS_MsgType >
int micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::robot_number_ [private]

Definition at line 279 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::sensory_feedback_ [private]

Definition at line 291 of file motivational_behavior.h.

template<typename VS_MsgType >
bool micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::sensory_feedback_exist_ [private]

Definition at line 294 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::sensory_feedback_timestamp_ [private]

Definition at line 292 of file motivational_behavior.h.

template<typename VS_MsgType >
std::string micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::sensory_feedback_topic_ [private]

Definition at line 282 of file motivational_behavior.h.

template<typename VS_MsgType >
ros::Subscriber micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::sub_0_ [private]

Definition at line 269 of file motivational_behavior.h.

template<typename VS_MsgType >
ros::Subscriber micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::sub_1_ [private]

Definition at line 270 of file motivational_behavior.h.

template<typename VS_MsgType >
ros::Subscriber micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::sub_2_ [private]

Definition at line 271 of file motivational_behavior.h.

template<typename VS_MsgType >
int micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::this_behavior_set_ID_ [private]

Definition at line 277 of file motivational_behavior.h.

template<typename VS_MsgType >
int micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::this_robot_ID_ [private]

Definition at line 276 of file motivational_behavior.h.

template<typename VS_MsgType >
double micros_mars_task_alloc::MotivationalBehavior< VS_MsgType >::threshold_ [private]

Definition at line 304 of file motivational_behavior.h.


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


micros_mars_task_alloc
Author(s): Minglong Li , Xiaodong Yi , Yanzhen Wang , Zhongxuan Cai
autogenerated on Mon Jul 1 2019 19:55:03