scoutos / scout / libscout / src / test_behaviors / ApproachEmitter.cpp @ 6ad8ef06
History | View | Annotate | Download (6.75 KB)
1 |
/**
|
---|---|
2 |
* Copyright (c) 2011 Colony Project
|
3 |
*
|
4 |
* Permission is hereby granted, free of charge, to any person
|
5 |
* obtaining a copy of this software and associated documentation
|
6 |
* files (the "Software"), to deal in the Software without
|
7 |
* restriction, including without limitation the rights to use,
|
8 |
* copy, modify, merge, publish, distribute, sublicense, and/or sell
|
9 |
* copies of the Software, and to permit persons to whom the
|
10 |
* Software is furnished to do so, subject to the following
|
11 |
* conditions:
|
12 |
*
|
13 |
* The above copyright notice and this permission notice shall be
|
14 |
* included in all copies or substantial portions of the Software.
|
15 |
*
|
16 |
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
|
17 |
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
|
18 |
* OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
19 |
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
|
20 |
* HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
|
21 |
* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
22 |
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
|
23 |
* OTHER DEALINGS IN THE SOFTWARE.
|
24 |
*/
|
25 |
|
26 |
#include "ApproachEmitter.h" |
27 |
#define TOP_BOM 0 |
28 |
#define BOT_BOM 1 |
29 |
#define LEFT_EMITTER_ID 1 |
30 |
#define RIGHT_EMITTER_ID 0 |
31 |
|
32 |
|
33 |
#define LEFTSIDE 1 |
34 |
#define RIGHTSIDE 2 |
35 |
#define REAR 3 |
36 |
#define NEITHER 0 |
37 |
|
38 |
#define CENTRED 2 |
39 |
#define SEARCH 0 |
40 |
#define ADJUSTED 1 |
41 |
|
42 |
|
43 |
using namespace std; |
44 |
|
45 |
ApproachEmitter::ApproachEmitter(string scoutname, Sensors* sensors)
|
46 |
: Behavior(scoutname, "Approach Emitter", sensors) {
|
47 |
name = scoutname; |
48 |
scout_pos = new pos;
|
49 |
|
50 |
// initallize the side index values :D UGLY!!! But best solution so far
|
51 |
FRONT.push_back(0);
|
52 |
LEFT.push_back(1);
|
53 |
LEFT.push_back(2);
|
54 |
LEFT.push_back(3);
|
55 |
BACK.push_back(4);
|
56 |
BACK.push_back(5);
|
57 |
RIGHT.push_back(6);
|
58 |
RIGHT.push_back(7);
|
59 |
RIGHT.push_back(8);
|
60 |
FRONT.push_back(9);
|
61 |
|
62 |
} |
63 |
|
64 |
int ApproachEmitter::identifyPosition(
|
65 |
vector<uint32_t> readings, vector<uint32_t> senders) { |
66 |
int identified = SEARCH;
|
67 |
int top_em_count = 0; |
68 |
int bot_em_count = 0; |
69 |
if (accumulate(&(readings[RIGHT.front()]),
|
70 |
&(readings[RIGHT.back()])+1, 0) >= 2) { |
71 |
for (int i=RIGHT.front(); i<RIGHT.back(); i++) { |
72 |
top_em_count += (senders[i] == TOP_BOM); |
73 |
bot_em_count += (senders[i] == BOT_BOM); |
74 |
} |
75 |
if (top_em_count * bot_em_count != 0) { |
76 |
return CENTRED;
|
77 |
} else if (top_em_count > 0) { |
78 |
motors->set_sides(-50, -50, MOTOR_PERCENT); |
79 |
} else {
|
80 |
motors->set_sides(50, 50, MOTOR_PERCENT); |
81 |
} |
82 |
identified = ADJUSTED; |
83 |
} else if (accumulate(&(readings[LEFT.front()]), |
84 |
&(readings[LEFT.back()])+1, 0) >= 2) { |
85 |
|
86 |
for (int i=LEFT.front(); i<LEFT.back(); i++) { |
87 |
top_em_count += (senders[i] == TOP_BOM); |
88 |
bot_em_count += (senders[i] == BOT_BOM); |
89 |
} |
90 |
if (top_em_count * bot_em_count != 0) { |
91 |
return CENTRED;
|
92 |
} else if (top_em_count > 0) { |
93 |
motors->set_sides(50, 50, MOTOR_PERCENT); |
94 |
} else {
|
95 |
motors->set_sides(-50, -50, MOTOR_PERCENT); |
96 |
} |
97 |
identified = ADJUSTED; |
98 |
} |
99 |
return identified;
|
100 |
} |
101 |
|
102 |
void ApproachEmitter::run() {
|
103 |
ROS_INFO("BOM Main Running");
|
104 |
BomReadings bomR; |
105 |
vector<uint32_t> r; |
106 |
vector<uint32_t> s; |
107 |
int identified = 0; |
108 |
while (ok()) {
|
109 |
bomR = bom->query(); |
110 |
r = bomR.readings; |
111 |
s = bomR.senders; |
112 |
identified = identifyPosition(r, s); |
113 |
if (identified == CENTRED) {
|
114 |
//ROS_INFO("break");
|
115 |
break;
|
116 |
} else if (identified == SEARCH) { |
117 |
motors->set_sides(10, 40, MOTOR_PERCENT); |
118 |
} |
119 |
} |
120 |
|
121 |
update_readings(); |
122 |
start_side = get_side(); |
123 |
|
124 |
while (ok() && ((start_side == LEFTSIDE && checkBOM(3, RIGHT_EMITTER_ID)) || |
125 |
(start_side == RIGHTSIDE && checkBOM(6, LEFT_EMITTER_ID)))) {
|
126 |
motors->set_sides(25, 25, MOTOR_PERCENT); |
127 |
update_readings(); |
128 |
|
129 |
} |
130 |
|
131 |
motors->set_sides(0, 0, MOTOR_PERCENT); |
132 |
|
133 |
|
134 |
while(ok() && reverse_park()) {
|
135 |
update_readings(); |
136 |
} |
137 |
|
138 |
|
139 |
//motors->set_sides(0,0,MOTOR_PERCENT);
|
140 |
ROS_INFO("done");
|
141 |
/*
|
142 |
while(ok()) {
|
143 |
update_readings();
|
144 |
if (at_destination()) {
|
145 |
motors->set_sides(0, 0, MOTOR_PERCENT);
|
146 |
ROS_INFO("done");
|
147 |
break;
|
148 |
}
|
149 |
else {
|
150 |
motors->set_sides(-20,-20,MOTOR_PERCENT);
|
151 |
|
152 |
}
|
153 |
}
|
154 |
*/
|
155 |
} |
156 |
|
157 |
bool ApproachEmitter::reverse_park() {
|
158 |
if(checkBOM(5, LEFT_EMITTER_ID) || |
159 |
checkBOM(4, RIGHT_EMITTER_ID)) { //move forward |
160 |
|
161 |
motors->set_sides(10, 10, MOTOR_PERCENT); |
162 |
} |
163 |
else if(checkBOM(4, LEFT_EMITTER_ID) && |
164 |
checkBOM(5, RIGHT_EMITTER_ID)) {
|
165 |
|
166 |
motors->set_sides(-20, -20, MOTOR_PERCENT); |
167 |
} |
168 |
else if (get_side() == REAR) { |
169 |
if (checkBOM(4,LEFT_EMITTER_ID) && |
170 |
!checkBOM(4, RIGHT_EMITTER_ID)) { //reverse right |
171 |
//ROS_INFO("correct left");
|
172 |
motors->set_sides(-20, -10, MOTOR_PERCENT); |
173 |
} |
174 |
else if (!checkBOM(4, LEFT_EMITTER_ID) && |
175 |
checkBOM(5, RIGHT_EMITTER_ID)) { //reverse left |
176 |
//ROS_INFO("correct right");
|
177 |
motors->set_sides(-10, -20, MOTOR_PERCENT); |
178 |
} |
179 |
else {
|
180 |
motors->set_sides(-20, -20, MOTOR_PERCENT); |
181 |
} |
182 |
} |
183 |
else {
|
184 |
if (start_side == RIGHTSIDE) { //reverseright |
185 |
motors->set_sides(-40, -10, MOTOR_PERCENT); |
186 |
} |
187 |
else { //reverseleft |
188 |
motors->set_sides(-10, -40, MOTOR_PERCENT); |
189 |
|
190 |
} |
191 |
} |
192 |
|
193 |
if (at_destination()) {
|
194 |
return false; |
195 |
} |
196 |
return true; |
197 |
} |
198 |
|
199 |
int ApproachEmitter::get_side() {
|
200 |
|
201 |
if ((readings[1] > 0 || readings[2] > 0|| readings[3] > 0) && |
202 |
(readings[6] == 0 && readings[7] == 0 && readings[8] == 0)) { |
203 |
return LEFTSIDE;
|
204 |
} |
205 |
else if ((readings[6] > 0 || readings[7] > 0|| readings[8] > 0) && |
206 |
(readings[1] == 0 && readings[2] == 0 && readings[3] == 0)) { |
207 |
return RIGHTSIDE;
|
208 |
} |
209 |
else if ((readings[4] > 0) || (readings[5] > 0)) { |
210 |
return REAR;
|
211 |
} |
212 |
else {
|
213 |
return NEITHER;
|
214 |
} |
215 |
} |
216 |
|
217 |
bool ApproachEmitter::checkBOM(int bNum, unsigned int ID) { |
218 |
if(readings[bNum] == true) { |
219 |
//ROS_INFO("Emitter ID: %d", senders[bNum]);
|
220 |
return senders[bNum] == ID;
|
221 |
} |
222 |
return false; |
223 |
|
224 |
} |
225 |
|
226 |
void ApproachEmitter::update_readings() {
|
227 |
BomReadings bomR = bom->query(); |
228 |
readings = bomR.readings; |
229 |
senders = bomR.senders; |
230 |
|
231 |
} |
232 |
|
233 |
bool ApproachEmitter::at_destination()
|
234 |
{ |
235 |
vector<uint32_t> readings = linesensor->query(); |
236 |
|
237 |
/* ROS_INFO("%d %d %d %d %d %d %d %d", readings[0], readings[1],
|
238 |
readings[2],readings[3],readings[4],readings[5],readings[6],readings[7]);
|
239 |
*/
|
240 |
//changed values so it detects solution
|
241 |
if ( readings[0] > 75 || |
242 |
readings[1] > 75 || |
243 |
readings[2] > 75 || |
244 |
readings[3] > 75 || |
245 |
readings[4] > 75 || |
246 |
readings[5] > 75 || |
247 |
readings[6] > 75 || |
248 |
readings[7] > 75 ) |
249 |
{ |
250 |
return true; |
251 |
} |
252 |
return false; |
253 |
} |