root / scout_avr / src / main.cpp @ 64aea12e
History | View | Annotate | Download (4.76 KB)
1 | 6e7f0a98 | Tom Mullins | #if 1 /////////////////////////////////////////////// |
---|---|---|---|
2 | 807483bf | Tom Mullins | |
3 | 49090532 | Tom Mullins | #include "ros.h" |
4 | 6e7f0a98 | Tom Mullins | #include "bom.h" |
5 | 47e26dee | Tom Mullins | #include "range.h" |
6 | 6c9146d5 | Tom Mullins | #include "stepper.h" |
7 | #include <std_msgs/Int16.h> // TODO remove |
||
8 | #include <bom/bom.h> |
||
9 | #include <sonar/sonar_distance.h> |
||
10 | #include <sonar/sonar_toggle.h> |
||
11 | #include <sonar/sonar_set_scan.h> |
||
12 | 47e26dee | Tom Mullins | #include <util/delay.h> |
13 | 88fb3a79 | Tom Mullins | |
14 | 6c9146d5 | Tom Mullins | /* Period of main loop in ms */
|
15 | 2853d46b | Tom Mullins | #define MAINLOOP_PERIOD 100//50 |
16 | 6c9146d5 | Tom Mullins | |
17 | char range_enabled = 0; |
||
18 | 49090532 | Tom Mullins | |
19 | 812788aa | Tom Mullins | void debug(const char *str) |
20 | { |
||
21 | 31f4a032 | Tom Mullins | } |
22 | |||
23 | cf115e3d | Tom Mullins | void callback(const std_msgs::Int16& msg) |
24 | 49090532 | Tom Mullins | { |
25 | } |
||
26 | |||
27 | 6c9146d5 | Tom Mullins | /* dammit, Priya, this capitalization just looks ridiculous */
|
28 | void range_toggle_cb(const sonar::sonar_toggleRequest& req, |
||
29 | sonar::sonar_toggleResponse& resp) |
||
30 | { |
||
31 | range_enabled = req.set_on; |
||
32 | 64aea12e | Tom Mullins | if (range_enabled)
|
33 | step_enable(); |
||
34 | else
|
||
35 | step_disable(); |
||
36 | 6c9146d5 | Tom Mullins | resp.ack = true;
|
37 | } |
||
38 | |||
39 | void range_set_scan_cb(const sonar::sonar_set_scanRequest& req, |
||
40 | sonar::sonar_set_scanResponse& resp) |
||
41 | { |
||
42 | step_sweep_bounds(req.stop_l, req.stop_r); |
||
43 | resp.ack = true;
|
||
44 | } |
||
45 | |||
46 | 49090532 | Tom Mullins | int main()
|
47 | 88fb3a79 | Tom Mullins | { |
48 | 6c9146d5 | Tom Mullins | unsigned long now, next; |
49 | unsigned int ranges[2]; |
||
50 | 6e7f0a98 | Tom Mullins | char i, id;
|
51 | 6c9146d5 | Tom Mullins | |
52 | 88fb3a79 | Tom Mullins | ros::NodeHandle nh; |
53 | 6c9146d5 | Tom Mullins | nh.initNode(); |
54 | 49090532 | Tom Mullins | |
55 | 6c9146d5 | Tom Mullins | /* To be removed later; just an example of a subscirber */
|
56 | ros::Subscriber<std_msgs::Int16> test_in("test_in", callback);
|
||
57 | nh.subscribe(test_in); |
||
58 | 88fb3a79 | Tom Mullins | |
59 | 2853d46b | Tom Mullins | /* Stepper */
|
60 | // TODO ROS messages to set bounds
|
||
61 | step_init(); |
||
62 | step_dir(1);
|
||
63 | step_set_size(STEP_WHOLE); |
||
64 | step_sweep_bounds(-26, 26); |
||
65 | |||
66 | 6c9146d5 | Tom Mullins | /* Range */
|
67 | 47e26dee | Tom Mullins | range_init(); |
68 | 6c9146d5 | Tom Mullins | sonar::sonar_distance range_msg; |
69 | 86b48573 | Tom Mullins | ros::Publisher range_pub("sonar_distance", &range_msg);
|
70 | 6c9146d5 | Tom Mullins | ros::ServiceServer |
71 | <sonar::sonar_toggleRequest, sonar::sonar_toggleResponse> |
||
72 | range_toggle("sonar_toggle", range_toggle_cb);
|
||
73 | ros::ServiceServer |
||
74 | <sonar::sonar_set_scanRequest, sonar::sonar_set_scanResponse> |
||
75 | range_set_scan("sonar_set_scan", range_set_scan_cb);
|
||
76 | 86b48573 | Tom Mullins | nh.advertise(range_pub); |
77 | 958699af | Tom Mullins | nh.advertiseService(range_toggle); |
78 | nh.advertiseService(range_set_scan); |
||
79 | 6c9146d5 | Tom Mullins | |
80 | /* BOM */
|
||
81 | 47e26dee | Tom Mullins | bom_init(); |
82 | 6c9146d5 | Tom Mullins | bom::bom bom_msg; |
83 | ros::Publisher bom_pub("bom", &bom_msg);
|
||
84 | 6e7f0a98 | Tom Mullins | nh.advertise(bom_pub); |
85 | 88fb3a79 | Tom Mullins | |
86 | 6e7f0a98 | Tom Mullins | id = 0;
|
87 | 6c9146d5 | Tom Mullins | next = 0;
|
88 | 88fb3a79 | Tom Mullins | while (1) |
89 | { |
||
90 | 6c9146d5 | Tom Mullins | nh.spinOnce(); |
91 | |||
92 | /* Skip loop if the loop period hasn't passed yet */
|
||
93 | /* TODO if we need more exact timing, we can enter a tight loop when now
|
||
94 | * gets close to next, and avoid the uncertainty of nh.spinOnce() */
|
||
95 | now = nh.getHardware()->time(); |
||
96 | if (now < next) {
|
||
97 | continue;
|
||
98 | } |
||
99 | next = now + MAINLOOP_PERIOD; |
||
100 | |||
101 | /* Temporary, for BOM testing */
|
||
102 | 6e7f0a98 | Tom Mullins | id++; |
103 | if (id == 0x40) { |
||
104 | id = 0;
|
||
105 | } |
||
106 | set_robot_id(id); |
||
107 | 47e26dee | Tom Mullins | bom_send(id & 1);
|
108 | 6c9146d5 | Tom Mullins | |
109 | /* BOM */
|
||
110 | 6e7f0a98 | Tom Mullins | for (i = 0; i < 4; i++) { |
111 | int msg = bom_get(i);
|
||
112 | if (msg != BOM_NO_DATA) {
|
||
113 | bom_msg.sender = bom_msg_get_robot_id(msg); |
||
114 | bom_msg.send_dir = bom_msg_get_dir(msg); |
||
115 | bom_msg.recv_dir = i; |
||
116 | bom_pub.publish(&bom_msg); |
||
117 | } |
||
118 | } |
||
119 | 47e26dee | Tom Mullins | |
120 | 6c9146d5 | Tom Mullins | /* Stepper / range sensor */
|
121 | 2853d46b | Tom Mullins | if (range_enabled) {
|
122 | step_sweep(); |
||
123 | range_measure(ranges); |
||
124 | range_msg.header.stamp = nh.now(); |
||
125 | range_msg.header.seq++; |
||
126 | range_msg.pos = 0; // TODO fill this |
||
127 | range_msg.distance0 = ranges[0];
|
||
128 | range_msg.distance1 = ranges[1];
|
||
129 | range_pub.publish(&range_msg); |
||
130 | } |
||
131 | 6c9146d5 | Tom Mullins | |
132 | 88fb3a79 | Tom Mullins | } |
133 | |||
134 | return 0; |
||
135 | 49090532 | Tom Mullins | } |
136 | 88fb3a79 | Tom Mullins | |
137 | 807483bf | Tom Mullins | #else /////////////////////////////////////////////// |
138 | |||
139 | extern "C" |
||
140 | 88fb3a79 | Tom Mullins | { |
141 | #include <stdlib.h> |
||
142 | #include <string.h> |
||
143 | fd73d758 | Tom Mullins | #include <avr/io.h> |
144 | #include <util/delay.h> |
||
145 | 88fb3a79 | Tom Mullins | } |
146 | |||
147 | 49090532 | Tom Mullins | #include "Atmega128rfa1.h" |
148 | 1c3c96ce | Tom Mullins | #include "range.h" |
149 | f115416e | Tom Mullins | #include "bom.h" |
150 | 6c9146d5 | Tom Mullins | #include "stepper.h" |
151 | 49090532 | Tom Mullins | |
152 | 31f4a032 | Tom Mullins | Atmega128rfa1 avr; |
153 | |||
154 | 812788aa | Tom Mullins | void debug(const char *str) |
155 | { |
||
156 | 31f4a032 | Tom Mullins | avr.puts(str); |
157 | } |
||
158 | |||
159 | 88fb3a79 | Tom Mullins | int main()
|
160 | { |
||
161 | 1c3c96ce | Tom Mullins | char buf[20]; |
162 | 86b48573 | Tom Mullins | //int i;
|
163 | //char id = 0;
|
||
164 | 2853d46b | Tom Mullins | /*unsigned long now, next = 0;
|
165 | unsigned int ranges[2];*/
|
||
166 | 88fb3a79 | Tom Mullins | avr.init(); |
167 | 1c3c96ce | Tom Mullins | range_init(); |
168 | f115416e | Tom Mullins | bom_init(); |
169 | 2853d46b | Tom Mullins | func step_sweep_cb = step_init(10);
|
170 | 6c9146d5 | Tom Mullins | step_sweep_bounds(-26, 26); |
171 | step_dir(1);
|
||
172 | 2853d46b | Tom Mullins | step_sweep_speed(50);
|
173 | PORTF |= _BV(PF4); |
||
174 | _delay_ms(500);
|
||
175 | PORTF = (PORTF & ~_BV(PF4)) | _BV(PF5); |
||
176 | _delay_ms(500);
|
||
177 | PORTF &= ~_BV(PF5); |
||
178 | 88fb3a79 | Tom Mullins | while (1) |
179 | { |
||
180 | 2853d46b | Tom Mullins | step_sweep_cb(); |
181 | _delay_ms(10);
|
||
182 | /*now = avr.time();
|
||
183 | 49090532 | Tom Mullins | if (now > next) {
|
184 | 2853d46b | Tom Mullins | next = now + 500;*/
|
185 | fd73d758 | Tom Mullins | /*ultoa(now, buf, 10);
|
186 | 812788aa | Tom Mullins | avr.puts(buf);
|
187 | fd73d758 | Tom Mullins | avr.puts("\r\n");*/
|
188 | 6c9146d5 | Tom Mullins | /*id++;
|
189 | 31f4a032 | Tom Mullins | if (id == 0x40) {
|
190 | id = 0;
|
||
191 | }
|
||
192 | 6c9146d5 | Tom Mullins | set_robot_id(id);*/
|
193 | 2853d46b | Tom Mullins | /*range_measure(ranges);
|
194 | 86b48573 | Tom Mullins | utoa(ranges[0], buf, 10);
|
195 | f115416e | Tom Mullins | avr.puts("Range: ");
|
196 | avr.puts(buf);
|
||
197 | avr.puts(", ");
|
||
198 | 86b48573 | Tom Mullins | utoa(ranges[1], buf, 10);
|
199 | avr.puts(buf);
|
||
200 | 2853d46b | Tom Mullins | avr.puts("\r\n");*/
|
201 | 6c9146d5 | Tom Mullins | /*for (i = 0; i < 4; i++) {
|
202 | f115416e | Tom Mullins | bom_send(i);
|
203 | int msg = bom_get(i);
|
||
204 | if (msg != BOM_NO_DATA) {
|
||
205 | avr.puts("BOM ");
|
||
206 | itoa(i, buf, 10);
|
||
207 | avr.puts(buf);
|
||
208 | avr.puts(": ");
|
||
209 | 31f4a032 | Tom Mullins | itoa(bom_msg_get_robot_id(msg), buf, 10);
|
210 | avr.puts(buf);
|
||
211 | avr.puts(" (");
|
||
212 | itoa(bom_msg_get_dir(msg), buf, 10);
|
||
213 | f115416e | Tom Mullins | avr.puts(buf);
|
214 | 31f4a032 | Tom Mullins | avr.puts(")\r\n");
|
215 | f115416e | Tom Mullins | }
|
216 | 6c9146d5 | Tom Mullins | }*/
|
217 | 2853d46b | Tom Mullins | //}
|
218 | 88fb3a79 | Tom Mullins | } |
219 | return 0; |
||
220 | cf115e3d | Tom Mullins | } |
221 | 807483bf | Tom Mullins | |
222 | #endif ////////////////////////////////////////////// |