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