Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / scout_teleop.cpp @ e1d66e9a

History | View | Annotate | Download (2.77 KB)

1
#include "scout_teleop.h"
2

    
3
TeleopScout::TeleopScout(std::string scoutname)
4
{
5
    fl_set = fr_set = bl_set = br_set = true;
6
    fl_speed = fr_speed = bl_speed = br_speed = 0;
7
    motors_pub = node.advertise<motors::set_motors>(
8
                    scoutname+"/set_motors", QUEUE_SIZE);
9
    key_input_sub = node.subscribe(scoutname+"/teleop_input",
10
                                        QUEUE_SIZE,
11
                                        &TeleopScout::teleop_input_callback,
12
                                        this);
13
}
14

    
15
void TeleopScout::teleop_input_callback(
16
            const scoutsim::teleop_input::ConstPtr& msg)
17
{
18
    last_key = msg->last_key;
19
    last_time = msg->header.stamp;
20
    ROS_INFO("received key: 0x%02X ", last_key);
21
    ROS_INFO("at last time: %f\n", last_time.toSec()); 
22
}
23

    
24
void TeleopScout::keyListenerLoop()
25
{
26
    while(ros::ok())
27
    {
28
        if(last_time + MAX_WAIT_TIME < ros::Time::now())
29
        {
30
            switch(last_key)
31
            {
32
                case KEYCODE_L:
33
                    //ROS_INFO("LEFT");
34
                    fl_speed = bl_speed = 200;
35
                    fr_speed = br_speed = -200;
36
                    break;
37
                case KEYCODE_R:
38
                    //ROS_INFO("RIGHT");
39
                    fl_speed = bl_speed = -200;
40
                    fr_speed = br_speed = 200;
41
                    break;
42
                case KEYCODE_U:
43
                    //ROS_INFO("UP");
44
                    fl_speed = bl_speed = 200;
45
                    fr_speed = br_speed = 200;
46
                    break;
47
                case KEYCODE_D:
48
                    //ROS_INFO("DOWN");
49
                    fl_speed = bl_speed = -200;
50
                    fr_speed = br_speed = -200;
51
                    break;
52
                default:
53
                    //don't publish a message yet; no change to key, 
54
                    // and no timeout yet
55
                    ROS_INFO("no time out yet\n");
56
                    ros::spinOnce();
57
                    continue;
58
                    break;
59
            }
60
        }
61
        else if (fl_speed != 0 || fr_speed != 0 || 
62
                 bl_speed != 0 || br_speed != 0)
63
        {
64
            fl_speed = fr_speed = bl_speed = br_speed = 0;
65
        }
66

    
67
        //send command to the motors
68
        motors::set_motors msg;
69
        msg.fl_set = fl_set;
70
        msg.fr_set = fr_set;
71
        msg.bl_set = bl_set;
72
        msg.br_set = br_set;
73
        msg.fl_speed = fl_speed;
74
        msg.fr_speed = fr_speed;
75
        msg.bl_speed = bl_speed;
76
        msg.br_speed = br_speed;
77
        motors_pub.publish(msg);
78
                
79
        ros::spinOnce();
80
    }
81
    return;
82
}
83

    
84
int main(int argc, char** argv)
85
{
86
    ros::init(argc, argv, "scout_teleop");
87
    TeleopScout teleop_scout = TeleopScout("scout1");
88
    
89
    teleop_scout.keyListenerLoop();
90

    
91
    return(0);
92
}