Project

General

Profile

Revision dcf49526

IDdcf49526269a0df9a064ad37dfff13efdea10d97

Added by Priya about 11 years ago

Overwrote the ROS sigint handler so now behaviours stop and die and stop motors upon exiting.

View differences:

scout/libscout/src/Behavior.cpp
38 38

  
39 39
using namespace std;
40 40

  
41
bool Behavior::keep_running;
42

  
41 43
/**
42 44
 * Constructs a behavior and sets up all control classes.
43 45
 *
......
50 52
 */
51 53
Behavior::Behavior(string scoutname, string my_name, Sensors * sensors)
52 54
{
53

  
54 55
    name = my_name;
56
    keep_running = true;
55 57
    sensors->init(&motors, &buttons, &sonar, &encoders, &linesensor,
56 58
                        &wl_sender, &wl_receiver);
57 59
    wl_receiver->register_callback(std::bind(&Behavior::default_callback,
......
66 68
Behavior::~Behavior()
67 69
{
68 70
  motors->set_sides(0, 0, MOTOR_ABSOLUTE);
69
  ROS_INFO("I get called");
70 71
  spinOnce();
71
  loop_rate->sleep();
72 72
  delete wl_receiver;
73 73
  delete loop_rate;
74 74
}
......
86 86
 */
87 87
bool Behavior::ok()
88 88
{
89
    return ros::ok();
89
    return keep_running;
90 90
}
91 91

  
92 92
/**

Also available in: Unified diff