Project

General

Profile

Revision 493cca7c

ID493cca7c321081c9bdcb1cf72714506ef1310954

Added by Chris Burchhardt over 12 years ago

basic (not-yet-working) flight control via keyboard

View differences:

mikrokopter/CMakeLists.txt
26 26
target_link_libraries(${PROJECT_NAME} serial)
27 27

  
28 28
rosbuild_add_executable(externctrl_client src/externctrl_client.cpp)
29
rosbuild_add_executable(wasd_nav src/wasd_nav.cpp src/nav_lib.cpp)
30 29
rosbuild_add_executable(keyboard_control src/keyboard_control.cpp src/nav_lib.cpp)
mikrokopter/launch/mikrokopter.launch
2 2

  
3 3
  <node name="mikrokopter" pkg="mikrokopter" 	type="mikrokopter">
4 4
    
5
    <param name="port" value="/dev/ttyACM0" />
5
    <param name="port" value="/dev/ttyUSB0" />
6 6
    	
7 7
    <param name="req_version_rate" value="0.0" />	
8 8
    <param name="req_version_addr" value="97" />
mikrokopter/src/keyboard_control.cpp
11 11
#include <termios.h>
12 12
#include <stdio.h>
13 13

  
14
#include "nav_lib.h"
15

  
14 16
#define KEYCODE_R 0x43 
15 17
#define KEYCODE_L 0x44
16 18
#define KEYCODE_U 0x41
......
44 46

  
45 47
void KeyboardControl::keyLoop()
46 48
{
49
    
50
    ros::NodeHandle n;
51
    ros::Publisher pub = n.advertise<mikrokopter::Control>("/mikrokopter/req_set_control", 100);
52

  
53
    mikrokopter::Control req;
54

  
55
    ros::Rate loop_rate(25);
56
    
47 57
    char c;
48 58
    bool dirty=false;
49 59

  
......
77 87
        {
78 88
            case KEYCODE_L:
79 89
            case 'a':
80
                ROS_INFO("W");
90
                ROS_INFO("A");
91
                left(req);
81 92
                dirty = true;
82 93
                break;
83 94
            case KEYCODE_R:
84 95
            case 'd':
85
                ROS_INFO("E");
96
                ROS_INFO("D");
97
                right(req);
86 98
                dirty = true;
87 99
                break;
88 100
            case KEYCODE_U:
89 101
            case 'w':
90
                ROS_INFO("N");
102
                ROS_INFO("W");
103
                forward(req);
91 104
                dirty = true;
92 105
                break;
93 106
            case KEYCODE_D:
94 107
            case 's':
95
                ROS_INFO("S");
108
                ROS_INFO("B");
109
                backward(req);
96 110
                dirty = true;
97 111
                break;
98 112
            case 'r':
99 113
                ROS_INFO("UP");
114
                //set_throttle(&pub, );
100 115
                break;
101 116
            case 'f':
102 117
                ROS_INFO("DOWN");
118
                //set_throttle(&pub);
103 119
                break;
104 120
        }
105 121

  
106 122
        if(dirty)
107 123
        {
124
            pub.publish(req);
125
            ros::spinOnce();
108 126
            dirty=false;
109 127
        }
110 128
    }
mikrokopter/src/nav_lib.cpp
1 1
#include "nav_lib.h"
2 2

  
3
void set_roll_pitch(ros::Publisher& pub, int roll, int pitch) {
4
    mikrokopter::Control req;
3

  
4
void init_control_msg(mikrokopter::Control& req)
5
{
5 6
    req.digital[0] = 0;
6 7
    req.digital[1] = 0;
7 8
    req.remoteKey = 0;
8
    req.pitch = roll;
9
    req.roll = pitch;
9
    req.pitch = 0;
10
    req.roll = 0;
10 11
    req.yaw = 0;
11 12
    req.thrust = 40;
12 13
    req.height = 0;
13 14
    req.free = 0;
14 15
    req.frame = 7;
15 16
    req.config = 1;
16
    pub.publish(req);
17
    ros::spinOnce();
18 17
}
19 18

  
20

  
21
void forward(ros::Publisher& pub)
19
void forward(mikrokopter::Control& req)
22 20
{
23
    set_roll_pitch(pub, -15, -15);
21
    req.roll = -15;
22
    req.pitch = -15;
24 23
}
25 24

  
26
void backward(ros::Publisher& pub)
25
void backward(mikrokopter::Control& req)
27 26
{
28
    set_roll_pitch(pub, 15, 15);
27
    req.roll = 15;
28
    req.pitch = 15;
29 29
}
30 30

  
31
void left(ros::Publisher& pub)
31
void left(mikrokopter::Control& req)
32 32
{
33
    set_roll_pitch(pub, -15, 15);
33
    req.roll = -15;
34
    req.pitch = 15;
34 35
}
35 36

  
36
void right(ros::Publisher& pub)
37
void right(mikrokopter::Control& req)
37 38
{
38
    set_roll_pitch(pub, 15, -15);
39
    req.roll = 15;
40
    req.pitch = -15;
39 41
}
40 42

  
41
void stop(ros::Publisher& pub)
43
void set_thrust(mikrokopter::Control& req, int thrust)
42 44
{
43
    set_roll_pitch(pub, 0, 0);
45
    req.thrust = thrust;
44 46
}
47

  
mikrokopter/src/nav_lib.h
1 1
#include "ros/ros.h"
2 2
#include "mikrokopter/Control.h"
3 3

  
4
void forward(ros::Publisher& pub);
5
void backward(ros::Publisher& pub);
6
void left(ros::Publisher& pub);
7
void right(ros::Publisher& pub);
8
void stop(ros::Publisher& pub);
4
void init_control_msg(mikrokopter::Control& req);
5
void forward(mikrokopter::Control& req);
6
void backward(mikrokopter::Control& req);
7
void left(mikrokopter::Control& req);
8
void right(mikrokopter::Control& req);
9
void set_thrust(mikrokopter::Control& req, int thrust);
10

  
mikrokopter/src/wasd_nav.cpp
1
#include "ros/ros.h"
2
#include "mikrokopter/Control.h"
3
#include "nav_lib.h"
4
#include <cstdlib>
5

  
6

  
7
int main(int argc, char **argv)
8
{
9
    ros::init(argc, argv, "mikrokopter_externctrl_client");
10

  
11
    ros::NodeHandle n;
12
    ros::Publisher pub = n.advertise<mikrokopter::Control>("/mikrokopter/req_set_control", 100);
13

  
14
    ros::Rate loop_rate(25);
15
    
16
    printf("moving\n");
17
    forward(pub);
18
    
19
    sleep(5);
20
    printf("evening out\n");
21
    stop(pub);
22
    
23
    return 0;
24
}

Also available in: Unified diff