Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / scout_teleop.cpp @ 4c495190

History | View | Annotate | Download (3.07 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
    ROS_INFO("waiting for userinput commands...\n");
27
    ROS_INFO("current max wait time is:  %f\n", MAX_WAIT_TIME.toSec());
28
    while(ros::ok())
29
    {
30
        // if we haven't passed the waiting threshold
31
        if(last_time + MAX_WAIT_TIME > ros::Time::now())
32
        {
33
            switch(last_key)
34
            {
35
                // TODO: for some reason negative speeds go forward, not backward
36
                
37
                case KEYCODE_L:
38
                    //ROS_INFO("LEFT");
39
                    fl_speed = bl_speed = 200;
40
                    fr_speed = br_speed = -200;
41
                    break;
42
                case KEYCODE_R:
43
                    //ROS_INFO("RIGHT");
44
                    fl_speed = bl_speed = -200;
45
                    fr_speed = br_speed = 200;
46
                    break;
47
                case KEYCODE_U:
48
                    //ROS_INFO("UP");
49
                    fl_speed = bl_speed = -200;
50
                    fr_speed = br_speed = -200;
51
                    break;
52
                case KEYCODE_D:
53
                    //ROS_INFO("DOWN");
54
                    fl_speed = bl_speed = 200;
55
                    fr_speed = br_speed = 200;
56
                    break;
57
                default:
58
                    //don't publish a message yet; no change to key, 
59
                    // and no timeout yet
60
                    //ROS_INFO("no time out yet\n");
61
                    ros::spinOnce();
62
                    continue;
63
                    break;
64
            }
65
        }
66
        else if (fl_speed != 0 || fr_speed != 0 || 
67
                 bl_speed != 0 || br_speed != 0)
68
        {
69
            ROS_INFO("no key press; stopping movement");
70
            fl_speed = fr_speed = bl_speed = br_speed = 0;
71
        }
72

    
73
        //send command to the motors
74
        motors::set_motors msg;
75
        msg.fl_set = fl_set;
76
        msg.fr_set = fr_set;
77
        msg.bl_set = bl_set;
78
        msg.br_set = br_set;
79
        msg.fl_speed = fl_speed;
80
        msg.fr_speed = fr_speed;
81
        msg.bl_speed = bl_speed;
82
        msg.br_speed = br_speed;
83
        motors_pub.publish(msg);
84
                
85
        ros::spinOnce();
86
    }
87
    return;
88
}
89

    
90
int main(int argc, char** argv)
91
{
92
    ros::init(argc, argv, "scout_teleop");
93
    TeleopScout teleop_scout = TeleopScout("scout1");
94
    
95
    teleop_scout.keyListenerLoop();
96

    
97
    return(0);
98
}