Project

General

Profile

Revision faa11f08

IDfaa11f08b06bf7e31069ba66d6bd28a308a5b730

Added by Priya about 11 years ago

Changed it so that all behaviors are not instantiated immediately. Also changed pause so it does not spam (0, 0) motor speeds.

View differences:

scout/libscout/src/Behavior.cpp
66 66
Behavior::~Behavior()
67 67
{
68 68
  motors->set_sides(0, 0, MOTOR_ABSOLUTE);
69
  ROS_INFO("I get called");
70
  spinOnce();
71
  loop_rate->sleep();
69 72
  delete wl_receiver;
70 73
  delete loop_rate;
71 74
}
scout/libscout/src/BehaviorList.cpp
1 1
#include "BehaviorList.h"
2 2

  
3 3

  
4
BehaviorList::BehaviorList(std::string scoutname, Sensors * sensor)
4
BehaviorList::BehaviorList()
5 5
{
6
  behavior_list.push_back((Behavior*)new pause_scout(scoutname, sensor));
7
  behavior_list.push_back((Behavior*)new draw_cw_circle(scoutname,sensor));
8
  behavior_list.push_back((Behavior*)new draw_ccw_circle(scoutname, sensor));
9
  behavior_list.push_back((Behavior*)new Odometry(scoutname, sensor));
10
  behavior_list.push_back((Behavior*)new navigationMap(scoutname, sensor));
11
  behavior_list.push_back((Behavior*)new Scheduler(scoutname, sensor));
12
  behavior_list.push_back((Behavior*)new WH_Robot(scoutname, sensor));
13
  behavior_list.push_back((Behavior*)new line_follow(scoutname, sensor));
14
  behavior_list.push_back((Behavior*)new wl_test(scoutname, sensor));
15
  behavior_list.push_back((Behavior*)new maze_solve(scoutname, sensor));
6
  behavior_list.push_back(behavior<pause_scout>);
7
  behavior_list.push_back(behavior<draw_cw_circle>);
8
  behavior_list.push_back(behavior<draw_ccw_circle>);
9
  behavior_list.push_back(behavior<Odometry>);
10
  behavior_list.push_back(behavior<navigationMap>);
11
  behavior_list.push_back(behavior<Scheduler>);
12
  behavior_list.push_back(behavior<WH_Robot>);
13
  behavior_list.push_back(behavior<line_follow>);
14
  behavior_list.push_back(behavior<wl_test>);
15
  behavior_list.push_back(behavior<maze_solve>);
16 16
  return;
17 17
}
18 18

  
scout/libscout/src/BehaviorList.h
3 3

  
4 4
#include "Behavior.h"
5 5
#include "behaviors/line_follow.h"
6
#include "behaviors/priya_draw_name.h"
6 7
#include "behaviors/draw_cw_circle.h"
7 8
#include "behaviors/draw_ccw_circle.h"
8 9
#include "behaviors/Odometry.h"
......
14 15
#include "behaviors/maze_solve.h"
15 16
#include "Sensors.h"
16 17

  
18
template<typename T> Behavior* behavior(std::string scoutname, Sensors* sensors){ return (Behavior*)new T(scoutname, sensors); } 
19

  
20
typedef Behavior* (* behavior_func)(std::string, Sensors*);
21

  
17 22
class BehaviorList
18 23
{
19 24
  public:
20
  std::vector<Behavior*> behavior_list;
25
  std::vector<behavior_func> behavior_list;
21 26

  
22 27
  //Constructor. Initializes behavior_list
23
  BehaviorList(std::string scoutname, Sensors* sensor);
28
  BehaviorList();
24 29
  //Destructor. Frees behavior_list;
25 30
  ~BehaviorList();
26 31
};
scout/libscout/src/BehaviorProcess.cpp
61 61
        ros::init(argc, argv, scoutname + "_behavior");
62 62
        // one Sensor instance per-class
63 63
        Sensors* sensors = new Sensors(scoutname);
64
        BehaviorList* list = new BehaviorList(scoutname, sensors);
65
        vector<Behavior*> behavior_list = list->behavior_list;
64
        BehaviorList* list = new BehaviorList();
65
        vector<behavior_func> behavior_list = list->behavior_list;
66 66
        if (behavior_num < (int)behavior_list.size())
67 67
        {
68
            (behavior_list[behavior_num])->run();
68
            Behavior* b = behavior_list[behavior_num](scoutname, sensors);
69
            b->run();
69 70
        }
70 71
        else
71 72
        {
scout/libscout/src/behaviors/pause_scout.cpp
27 27

  
28 28
void pause_scout::run()
29 29
{
30
  while(ok()){
31
	  motors->set_sides(0, 0, MOTOR_ABSOLUTE);
32
  }
30
  motors->set_sides(0, 0, MOTOR_ABSOLUTE);
31
  spinOnce();
32
  loop_rate->sleep();
33 33
}

Also available in: Unified diff