Project

General

Profile

Revision 4c495190

ID4c4951907381f815d37ca13a7226ed4814d1e59a

Added by roboclub about 12 years ago

reduced teleop delay, scout drives forward now

View differences:

scout/scoutsim/CMakeLists.txt
36 36
#rosbuild_add_executable(turtle_teleop_key tutorials/teleop_turtle_key.cpp)
37 37
#rosbuild_add_executable(draw_square tutorials/draw_square.cpp)
38 38
#rosbuild_add_executable(mimic tutorials/mimic.cpp)
39
#rosbuild_add_executable(scout_teleop src/scout_teleop.cpp)
40
#rosbuild_add_executable(scout_teleop_userinput src/scout_teleop_userinput.cpp)
39
rosbuild_add_executable(scout_teleop src/scout_teleop.cpp)
40
rosbuild_add_executable(scout_teleop_userinput src/scout_teleop_userinput.cpp)
scout/scoutsim/src/scout_teleop.cpp
32 32
        {
33 33
            switch(last_key)
34 34
            {
35
		// TODO: for some reason negative speeds go forward, not backward
36
		
35 37
                case KEYCODE_L:
36 38
                    //ROS_INFO("LEFT");
37 39
                    fl_speed = bl_speed = 200;
......
44 46
                    break;
45 47
                case KEYCODE_U:
46 48
                    //ROS_INFO("UP");
47
                    fl_speed = bl_speed = 200;
48
                    fr_speed = br_speed = 200;
49
                    fl_speed = bl_speed = -200;
50
                    fr_speed = br_speed = -200;
49 51
                    break;
50 52
                case KEYCODE_D:
51 53
                    //ROS_INFO("DOWN");
52
                    fl_speed = bl_speed = -200;
53
                    fr_speed = br_speed = -200;
54
                    fl_speed = bl_speed = 200;
55
                    fr_speed = br_speed = 200;
54 56
                    break;
55 57
                default:
56 58
                    //don't publish a message yet; no change to key, 
scout/scoutsim/src/scout_teleop.h
19 19
#define KEYCODE_S 0x73
20 20

  
21 21
// a second
22
#define MAX_WAIT_TIME ros::Duration(1, 0)
22
#define MAX_WAIT_TIME ros::Duration(0.5)
23 23

  
24 24
class TeleopScout
25 25
{
scout/scoutsim/src/scout_teleop_userinput.cpp
22 22
{
23 23
    // reset console mode to no longer be raw
24 24
    tcsetattr(kfd, TCSANOW, &cooked);
25
    return;
25
    ros::shutdown();
26
    exit(0);
26 27
}
27 28

  
28 29
void TeleopInput::keyLoop()
......
56 57
{
57 58
    ros::init(argc, argv, "scout_teleop_userinput");
58 59
    TeleopInput teleop_input = TeleopInput("scout1");
60
    //signal(SIGINT,quit);
59 61
    teleop_input.keyLoop();
60 62

  
61 63
    return(0);

Also available in: Unified diff