Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / libscout / src / test_behaviors / ApproachEmitter.cpp @ 61fb2529

History | View | Annotate | Download (6.21 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 NEITHER 0
36

    
37
#define CENTRED 2
38
#define SEARCH 0
39
#define ADJUSTED 1
40

    
41

    
42
using namespace std;
43

    
44
ApproachEmitter::ApproachEmitter(string scoutname, Sensors* sensors)
45
    : Behavior(scoutname, "Approach Emitter", sensors) {
46
    name = scoutname;
47
    scout_pos = new pos;
48

    
49
    // initallize the side index values :D UGLY!!! But best solution so far
50
    FRONT.push_back(0);
51
    LEFT.push_back(1);
52
    LEFT.push_back(2);
53
    LEFT.push_back(3);
54
    BACK.push_back(4);
55
    BACK.push_back(5);
56
    RIGHT.push_back(6);
57
    RIGHT.push_back(7);
58
    RIGHT.push_back(8);
59
    FRONT.push_back(9);
60

    
61
}
62

    
63
int ApproachEmitter::identifyPosition(
64
        vector<uint32_t> readings, vector<uint32_t> senders) {
65
    bool identified = SEARCH;
66
    int top_em_count = 0;
67
    int bot_em_count = 0;
68
    if (accumulate(&(readings[RIGHT.front()]),
69
                   &(readings[RIGHT.back()])+1, 0) >= 2) {
70
        for (int i=RIGHT.front(); i<RIGHT.back(); i++) {
71
            top_em_count += (senders[i] == TOP_BOM);
72
            bot_em_count += (senders[i] == BOT_BOM);
73
        }
74
        if (top_em_count * bot_em_count != 0) {
75
            return CENTRED;
76
        } else if (top_em_count > 0) {
77
            motors->set_sides(-50, -50, MOTOR_PERCENT);
78
        } else {
79
            motors->set_sides(50, 50, MOTOR_PERCENT);
80
        }
81
        identified = ADJUSTED;
82
    } else if (accumulate(&(readings[LEFT.front()]),
83
                   &(readings[LEFT.back()])+1, 0) >= 2) {
84

    
85
        for (int i=LEFT.front(); i<LEFT.back(); i++) {
86
            top_em_count += (senders[i] == TOP_BOM);
87
            bot_em_count += (senders[i] == BOT_BOM);
88
        }
89
        if (top_em_count * bot_em_count != 0) {
90
            return CENTRED;
91
        } else if (top_em_count > 0) {
92
            motors->set_sides(50, 50, MOTOR_PERCENT);
93
        } else {
94
            motors->set_sides(-50, -50, MOTOR_PERCENT);
95
        }
96
        identified = ADJUSTED;
97
    }
98
    return identified;
99
}
100

    
101
void ApproachEmitter::run() {
102
    ROS_INFO("BOM Main Running");
103
    BomReadings bomR;
104
    vector<uint32_t> r;
105
    vector<uint32_t> s;
106
    int identified = 0;
107
    while (ok()) {
108
        bomR = bom->query();
109
        r = bomR.readings;
110
        s = bomR.senders;
111
        identified = identifyPosition(r, s);
112
        if (identified == CENTRED) {
113
            ROS_INFO("break");
114
            break;
115
        } else if (identified == SEARCH) {
116
            motors->set_sides(10, 40, MOTOR_PERCENT);
117
        }
118
    }
119

    
120
    update_readings();
121
    start_side = get_side();
122

    
123
    while (ok() && ((start_side == LEFTSIDE && checkBOM(3, RIGHT_EMITTER_ID)) ||
124
           (start_side == RIGHTSIDE && checkBOM(6, LEFT_EMITTER_ID)))) {
125
       motors->set_sides(25, 25, MOTOR_PERCENT);
126
       update_readings();
127

    
128
     }
129

    
130
    motors->set_sides(0, 0, MOTOR_PERCENT);
131

    
132

    
133
    while(ok() && reverse_park()) {
134
        update_readings();
135
    }
136

    
137

    
138
    //motors->set_sides(0,0,MOTOR_PERCENT);
139
    ROS_INFO("done");
140
/*
141
    while(ok()) {
142
        update_readings();
143
        if (at_destination()) {
144
              motors->set_sides(0, 0, MOTOR_PERCENT);
145
          ROS_INFO("done");
146
          break;
147
        }
148
        else {
149
          motors->set_sides(-20,-20,MOTOR_PERCENT);
150

151
        }
152
    }
153
*/
154
}
155

    
156
bool ApproachEmitter::reverse_park() {
157
    if(checkBOM(5, LEFT_EMITTER_ID) ||
158
       checkBOM(4, RIGHT_EMITTER_ID)) { //move forward
159

    
160
        motors->set_sides(10, 10, MOTOR_PERCENT);
161
    }
162
    else if(checkBOM(4, LEFT_EMITTER_ID) &&
163
            checkBOM(5, RIGHT_EMITTER_ID)) {
164

    
165
        motors->set_sides(-20, -20, MOTOR_PERCENT);
166
            if (at_destination()) {
167
          return false;
168
        }
169
    }
170
    else {
171
        if (start_side == RIGHTSIDE) { //reverseright
172
            motors->set_sides(-40, -10, MOTOR_PERCENT);
173
        }
174
        else { //reverseleft
175
            motors->set_sides(-10, -40, MOTOR_PERCENT);
176

    
177
        }
178
    }
179
    return true;
180
}
181

    
182
int ApproachEmitter::get_side() {
183

    
184
    if ((readings[1] > 0 || readings[2] > 0|| readings[3] > 0) &&
185
        (readings[6] == 0 && readings[7] == 0 && readings[8] == 0)) {
186
        return LEFTSIDE;
187
    }
188
    else if ((readings[6] > 0 || readings[7] > 0|| readings[8] > 0) &&
189
        (readings[1] == 0 && readings[2] == 0 && readings[3] == 0)) {
190
        return RIGHTSIDE;
191
    }
192
    else {
193
        return NEITHER;
194
    }
195
}
196

    
197
bool ApproachEmitter::checkBOM(int bNum, unsigned int ID) {
198
    if(readings[bNum] == true) {
199
        //ROS_INFO("Emitter ID: %d", senders[bNum]);
200
        return senders[bNum] == ID;
201
    }
202
    return false;
203

    
204
}
205

    
206
void ApproachEmitter::update_readings() {
207
    BomReadings bomR = bom->query();
208
    readings = bomR.readings;
209
    senders = bomR.senders;
210

    
211
}
212

    
213
bool ApproachEmitter::at_destination()
214
{
215
    vector<uint32_t> readings = linesensor->query();
216

    
217
/*   ROS_INFO("%d %d %d %d %d %d %d %d", readings[0], readings[1],
218
        readings[2],readings[3],readings[4],readings[5],readings[6],readings[7]);
219
*/
220
    //changed values so it detects solution
221
    if ( readings[0] > 75 ||
222
         readings[1] > 75 ||
223
         readings[2] > 75 ||
224
         readings[3] > 75 ||
225
         readings[4] > 75 ||
226
         readings[5] > 75 ||
227
         readings[6] > 75 ||
228
         readings[7] > 75 )
229
    {
230
        return true;
231
    }
232
    return false;
233
}