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