Project

General

Profile

Revision 31be19a6

ID31be19a6f1dbf2140fc23d0e97e1a5a706cb78b8

Added by Priya about 12 years ago

Behaviours now have names!

View differences:

scout/libscout/src/Behavior.cpp
48 48
 * @param scoutname If nonempty, specifies which scout in the simulator
49 49
 *                  will be controlled by this behavior.
50 50
 */
51
Behavior::Behavior(string scoutname)
51
Behavior::Behavior(string scoutname, char* my_name)
52 52
{
53
    name = my_name;
54

  
53 55
    motors = new MotorControl(node, scoutname);
54 56
    buttons = new ButtonControl(node, scoutname);
55 57
    sonar = new SonarControl(node, scoutname);
scout/libscout/src/Behavior.h
51 51
{
52 52
    public:
53 53
        // Initializes ROS for behavior
54
        Behavior(std::string scoutname);
54
        Behavior(std::string scoutname, char* name);
55 55

  
56 56
        /// Extended by subclasses to actually run the behavior.
57 57
        virtual void run() = 0;
58 58

  
59
        //Name of behaviour
60
        const char* name;
61

  
59 62
    protected:
60 63
        ros::NodeHandle node;
61 64

  
scout/libscout/src/BehaviorProcess.cpp
39 39
{
40 40
    string scoutname = "";
41 41
    int behavior_num;
42
    string behavior_name = "";
42 43

  
43 44
    // Running with no arguments only supports one scout. Check in case
44 45
    // the user meant to specify a scout in the arguments.
45
    if (argc != 3)
46
    if (argc != 4)
46 47
    {
47 48
        cout << "You have started this behavior in hardware mode." << endl
48 49
             << "To start in software mode, use: " << argv[0]
......
53 54
        // Use the provided scoutname for simulator messages
54 55
        scoutname = argv[1];
55 56
        behavior_num = atoi(argv[2]);
57
        behavior_name = argv[3];
56 58

  
57
        ros::init(argc, argv, "priya_behavior");
59
        ros::init(argc, argv, behavior_name);
58 60

  
59 61
        BehaviorList* list = new BehaviorList(scoutname);
60 62
        vector<Behavior*> behavior_list = list->behavior_list;
scout/libscout/src/behaviors/Odometry.cpp
4 4
using namespace std;
5 5

  
6 6
/** Set up the odometry node and prepare communcations over ROS */
7
Odometry::Odometry(string scoutname):Behavior(scoutname)
7
Odometry::Odometry(string scoutname):Behavior(scoutname, "odometry")
8 8
{
9 9
  scout_pos = new pos;
10 10
}
......
17 17

  
18 18
  /* TODO: Get current encoder ticks */
19 19
  encoder_readings scout_enc = encoders->query();
20
    motor_fl_dist = scout_enc.fl_ticks;
21
    motor_fr_dist = scout_enc.fr_ticks;
22
    motor_bl_dist = scout_enc.bl_ticks;
23
    motor_br_dist = scout_enc.br_ticks;
24

  
25
//  msg_time_in = ros::WallTime::now();
20
  motor_fl_dist = scout_enc.fl_ticks;
21
  motor_fr_dist = scout_enc.fr_ticks;
22
  motor_bl_dist = scout_enc.bl_ticks;
23
  motor_br_dist = scout_enc.br_ticks;
24
/**
25
  motor_fl_dist = scout_enc.fl_ticks - motor_fl_ticks;
26
  motor_fr_dist = scout_enc.fr_ticks - motor_fr_ticks;
27
  motor_bl_dist = scout_enc.bl_ticks - motor_bl_ticks;
28
  motor_br_dist = scout_enc.br_ticks - motor_br_ticks;
29
**/
26 30

  
27 31
  left_dist = DIST_PER_TICK*(motor_fl_dist + motor_bl_dist)/2;
28 32
  right_dist = DIST_PER_TICK*(motor_fr_dist + motor_br_dist)/2;
29 33

  
30
//  left_vel = left_dist/msg_time_iin;
31
//  right_vel = right_dist/msg_time_in;
32

  
33 34
  total_dist = (left_dist+right_dist)/2;
34 35
  theta = (right_dist - left_dist)/WHEEL_BASE;
35 36

  
36 37
  scout_pos->x = total_dist*sin(theta);
37 38
  scout_pos->y = total_dist*cos(theta);
38

  
39
 /* TODO: Publish x and y pos */
39
  scout_pos->theta = theta;
40

  
41
/**
42
  //Save state for next time in.
43
  motor_fl_ticks = scout_enc.fl_ticks;
44
  motor_fr_ticks = scout_enc.fr_ticks;
45
  motor_bl_ticks = scout_enc.bl_ticks;
46
  motor_br_ticks = scout_enc.br_ticks;
47
**/
40 48
 return;
41 49
}
42 50

  
......
45 53
  while(ok())
46 54
  {
47 55
    get_position();
48
    ROS_INFO("Scout is at x: %f  y: %f \n", scout_pos->x, scout_pos->y);
56
    //TODO publish position
57
    ROS_INFO("Scout is at x: %f  y: %f theta: %f\n", scout_pos->x, scout_pos->y, scout_pos->theta);
49 58
  }
50 59
}
scout/libscout/src/behaviors/Odometry.h
4 4
#include "../Behavior.h"
5 5

  
6 6

  
7
#define WHEEL_RADIUS  .5
7
#define WHEEL_RADIUS  5
8 8
#define WHEEL_CIRCUM  (2*M_PI*WHEEL_RADIUS)
9
#define WHEEL_BASE    3
10
#define ENCODER_COUNT 88
9
#define WHEEL_BASE    2
10
#define ENCODER_COUNT 8800000000
11 11
#define DIST_PER_TICK (WHEEL_CIRCUM/ENCODER_COUNT)
12 12

  
13 13
typedef struct{
14 14
  float x;
15 15
  float y;
16
  float theta;
16 17
} pos;
17 18

  
18 19
class Odometry : Behavior{
......
36 37
    ros::ServiceClient query_encoders_client;
37 38

  
38 39
    float msg_time_in;
40

  
39 41
    float motor_fl_dist;
40 42
    float motor_fr_dist;
41 43
    float motor_bl_dist;
42 44
    float motor_br_dist;
43 45

  
46
    float motor_fl_ticks;
47
    float motor_fr_ticks;
48
    float motor_bl_ticks;
49
    float motor_br_ticks;
50
    float scout_theta;
51

  
44 52
    pos* scout_pos;
45 53
};
46 54

  
scout/libscout/src/behaviors/draw_ccw_circle.h
32 32
{
33 33
    public:
34 34
        /// @todo Is this the best way to inherit the Behavior constructor?
35
        draw_ccw_circle(std::string scoutname) : Behavior(scoutname) {};
35
        draw_ccw_circle(std::string scoutname) : Behavior(scoutname, "draw_ccw_circle"){ };
36 36

  
37 37
        /** Actually executes the behavior. */
38 38
        void run();
scout/libscout/src/behaviors/draw_cw_circle.h
32 32
{
33 33
    public:
34 34
        /// @todo Is this the best way to inherit the Behavior constructor?
35
        draw_cw_circle(std::string scoutname) : Behavior(scoutname) {};
35
        draw_cw_circle(std::string scoutname) : Behavior(scoutname, "draw_cw_circle") {};
36 36

  
37 37
        /** Actually executes the behavior. */
38 38
        void run();
scout/libscout/src/behaviors/lineDrive.cpp
15 15

  
16 16
#include "line_drive.h"
17 17

  
18
line_drive::line_drive(String scoutname): Behavior(scoutname)
18
line_drive::line_drive(String scoutname): Behavior(scoutname, "line_drive")
19 19
{
20 20
  line_drive_init();
21 21
  line_follow_init();
scout/libscout/src/behaviors/navigationMap.cpp
1 1
#include "navigationMap.h"
2 2

  
3 3
/** @brief Initializes the map */
4
navigationMap::navigationMap(std::string scoutname) : Behavior(scoutname)
4
navigationMap::navigationMap(std::string scoutname) : Behavior(scoutname, "navigationMap")
5 5
{
6 6
  /** Initialize Map 
7 7
   *
scout/libscout/src/behaviors/trafficNavigation.h
136 136
class trafficNavigation : Behavior
137 137
{
138 138
    public:
139
        trafficNavigation(std::string scoutname) : Behavior(scoutname) {};
139
        trafficNavigation(std::string scoutname) : Behavior(scoutname, "traffic_nav") {};
140 140

  
141 141
        void run();
142 142
		int wirelessPacketHandle(int state);

Also available in: Unified diff