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