root / scout_avr / src / main.cpp @ 807483bf
History | View | Annotate | Download (1.4 KB)
1 | 807483bf | Tom Mullins | #if 0 ///////////////////////////////////////////////
|
---|---|---|---|
2 | |||
3 | 49090532 | Tom Mullins | #include "ros.h"
|
4 | cf115e3d | Tom Mullins | #include <std_msgs/Int16.h>
|
5 | 88fb3a79 | Tom Mullins | |
6 | 49090532 | Tom Mullins | ros::Publisher *ptest_out;
|
7 | |||
8 | cf115e3d | Tom Mullins | void callback(const std_msgs::Int16& msg)
|
9 | 49090532 | Tom Mullins | {
|
10 | ptest_out->publish(&msg);
|
||
11 | }
|
||
12 | |||
13 | int main()
|
||
14 | 88fb3a79 | Tom Mullins | {
|
15 | ros::NodeHandle nh;
|
||
16 | cf115e3d | Tom Mullins | std_msgs::Int16 msg;
|
17 | ros::Subscriber<std_msgs::Int16> test_in("test_in", callback);
|
||
18 | 49090532 | Tom Mullins | ros::Publisher test_out("test_out", &msg);
|
19 | |||
20 | ptest_out = &test_out;
|
||
21 | 88fb3a79 | Tom Mullins | |
22 | 49090532 | Tom Mullins | msg.data = 0;
|
23 | 88fb3a79 | Tom Mullins | nh.initNode();
|
24 | 49090532 | Tom Mullins | nh.subscribe(test_in);
|
25 | nh.advertise(test_out);
|
||
26 | 88fb3a79 | Tom Mullins | |
27 | while (1)
|
||
28 | {
|
||
29 | nh.spinOnce();
|
||
30 | }
|
||
31 | |||
32 | return 0;
|
||
33 | 49090532 | Tom Mullins | }
|
34 | 88fb3a79 | Tom Mullins | |
35 | 807483bf | Tom Mullins | #else ///////////////////////////////////////////////
|
36 | |||
37 | extern "C" |
||
38 | 88fb3a79 | Tom Mullins | { |
39 | #include <stdlib.h> |
||
40 | #include <string.h> |
||
41 | } |
||
42 | |||
43 | 49090532 | Tom Mullins | #include "Atmega128rfa1.h" |
44 | 1c3c96ce | Tom Mullins | #include "range.h" |
45 | 49090532 | Tom Mullins | |
46 | 88fb3a79 | Tom Mullins | int main()
|
47 | { |
||
48 | 1c3c96ce | Tom Mullins | char buf[20]; |
49 | cf115e3d | Tom Mullins | unsigned long now, next = 0; |
50 | 88fb3a79 | Tom Mullins | Atmega128rfa1 avr; |
51 | avr.init(); |
||
52 | 1c3c96ce | Tom Mullins | range_init(); |
53 | 88fb3a79 | Tom Mullins | while (1) |
54 | { |
||
55 | 49090532 | Tom Mullins | now = avr.time(); |
56 | if (now > next) {
|
||
57 | 1c3c96ce | Tom Mullins | next = now + 100;
|
58 | ec9e417d | Tom Mullins | utoa(range_get(0), buf, 10); |
59 | 1c3c96ce | Tom Mullins | avr.write((uint8_t*) buf, strlen(buf)); |
60 | 807483bf | Tom Mullins | avr.write((uint8_t*) ", ", 2); |
61 | utoa(range_get(1), buf, 10); |
||
62 | avr.write((uint8_t*) buf, strlen(buf)); |
||
63 | /*int data = avr.read();
|
||
64 | cf115e3d | Tom Mullins | if (data >= 0)
|
65 | {
|
||
66 | uint8_t data8 = data;
|
||
67 | avr.write((uint8_t*) "Received ", 9);
|
||
68 | avr.write(&data8, 1);
|
||
69 | }
|
||
70 | else
|
||
71 | 807483bf | Tom Mullins | avr.write((uint8_t*) ".", 1);*/
|
72 | 1c3c96ce | Tom Mullins | avr.write((uint8_t*) "\r\n", 2); |
73 | 49090532 | Tom Mullins | } |
74 | 88fb3a79 | Tom Mullins | } |
75 | return 0; |
||
76 | cf115e3d | Tom Mullins | } |
77 | 807483bf | Tom Mullins | |
78 | #endif ////////////////////////////////////////////// |