scoutos / scout / libscout / src / test_behaviors / ApproachEmitter.cpp @ fb61cb17
History | View | Annotate | Download (3.35 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 |
|
30 |
using namespace std; |
31 |
|
32 |
ApproachEmitter::ApproachEmitter(string scoutname, Sensors* sensors)
|
33 |
: Behavior(scoutname, "Approach Emitter", sensors) {
|
34 |
name = scoutname; |
35 |
scout_pos = new pos;
|
36 |
|
37 |
// initallize the side index values :D UGLY!!! But best solution so far
|
38 |
FRONT.push_back(0);
|
39 |
LEFT.push_back(1);
|
40 |
LEFT.push_back(2);
|
41 |
LEFT.push_back(3);
|
42 |
BACK.push_back(4);
|
43 |
BACK.push_back(5);
|
44 |
RIGHT.push_back(6);
|
45 |
RIGHT.push_back(7);
|
46 |
RIGHT.push_back(8);
|
47 |
FRONT.push_back(9);
|
48 |
|
49 |
} |
50 |
|
51 |
int ApproachEmitter::identifyPosition(
|
52 |
vector<uint32_t> readings, vector<uint32_t> senders) { |
53 |
bool identified = 0; |
54 |
int top_em_count = 0; |
55 |
int bot_em_count = 0; |
56 |
if (accumulate(&(readings[RIGHT.front()]),
|
57 |
&(readings[RIGHT.back()])+1, 0) >= 2) { |
58 |
for (int i=RIGHT.front(); i<RIGHT.back(); i++) { |
59 |
top_em_count += (senders[i] == TOP_BOM); |
60 |
bot_em_count += (senders[i] == BOT_BOM); |
61 |
} |
62 |
if (top_em_count * bot_em_count != 0) { |
63 |
//ROS_INFO("HAND OVER TO HUIJUN!");
|
64 |
} else if (top_em_count > 0) { |
65 |
motors->set_sides(-50, -50, MOTOR_PERCENT); |
66 |
} else {
|
67 |
motors->set_sides(50, 50, MOTOR_PERCENT); |
68 |
} |
69 |
identified = 1;
|
70 |
} else if (accumulate(&(readings[LEFT.front()]), |
71 |
&(readings[LEFT.back()])+1, 0) >= 2) { |
72 |
|
73 |
for (int i=LEFT.front(); i<LEFT.back(); i++) { |
74 |
top_em_count += (senders[i] == TOP_BOM); |
75 |
bot_em_count += (senders[i] == BOT_BOM); |
76 |
} |
77 |
if (top_em_count * bot_em_count != 0) { |
78 |
} else if (top_em_count > 0) { |
79 |
motors->set_sides(50, 50, MOTOR_PERCENT); |
80 |
} else {
|
81 |
motors->set_sides(-50, -50, MOTOR_PERCENT); |
82 |
} |
83 |
identified = 1;
|
84 |
} |
85 |
return identified;
|
86 |
} |
87 |
|
88 |
void ApproachEmitter::run() {
|
89 |
ROS_INFO("BOM Main Running");
|
90 |
BomReadings bomR; |
91 |
vector<uint32_t> r; |
92 |
vector<uint32_t> s; |
93 |
while (ok()) {
|
94 |
bomR = bom->query(); |
95 |
r = bomR.readings; |
96 |
s = bomR.senders; |
97 |
if (identifyPosition(r, s)) {
|
98 |
// do nothing
|
99 |
} else {
|
100 |
motors->set_sides(0, 50, MOTOR_PERCENT); |
101 |
} |
102 |
} |
103 |
while (ok()) {}
|
104 |
} |