Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / scoutsim / src / sim_frame.cpp @ 46ed9b9b

History | View | Annotate | Download (27.8 KB)

1
/**
2
 * The code in this package was developed using the structure of Willow
3
 * Garage's turtlesim package.  It was modified by the CMU Robotics Club
4
 * to be used as a simulator for the Colony Scout robot.
5
 *
6
 * All redistribution of this code is limited to the terms of Willow Garage's
7
 * licensing terms, as well as under permission from the CMU Robotics Club.
8
 * 
9
 * Copyright (c) 2011 Colony Project
10
 * 
11
 * Permission is hereby granted, free of charge, to any person
12
 * obtaining a copy of this software and associated documentation
13
 * files (the "Software"), to deal in the Software without
14
 * restriction, including without limitation the rights to use,
15
 * copy, modify, merge, publish, distribute, sublicense, and/or sell
16
 * copies of the Software, and to permit persons to whom the
17
 * Software is furnished to do so, subject to the following
18
 * conditions:
19
 * 
20
 * The above copyright notice and this permission notice shall be
21
 * included in all copies or substantial portions of the Software.
22
 * 
23
 * Copyright (c) 2009, Willow Garage, Inc.
24
 * All rights reserved.
25
 * 
26
 * Redistribution and use in source and binary forms, with or without
27
 * modification, are permitted provided that the following conditions are met:
28
 * 
29
 *    Redistributions of source code must retain the above copyright
30
 *       notice, this list of conditions and the following disclaimer.
31
 *    Redistributions in binary form must reproduce the above copyright
32
 *       notice, this list of conditions and the following disclaimer in the
33
 *       documentation and/or other materials provided with the distribution.
34
 *    Neither the name of the Willow Garage, Inc. nor the names of its
35
 *       contributors may be used to endorse or promote products derived from
36
 *       this software without specific prior written permission.
37
 * 
38
 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
39
 * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
40
 * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
41
 * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
42
 * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
43
 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
44
 * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
45
 * OTHER DEALINGS IN THE SOFTWARE.
46
 */
47

    
48
/**
49
 * @file sim_frame.cpp
50
 *
51
 * @ingroup scoutsim
52
 * @{
53
 */
54

    
55
#include "sim_frame.h"
56

    
57
#include <stdio.h>
58

    
59
#include <ros/package.h>
60
#include <cstdlib>
61
#include <ctime>
62

    
63
using namespace std;
64

    
65
namespace scoutsim
66
{
67
    SimFrame::SimFrame(wxWindow* parent, string map_name)
68
        : wxFrame(parent, wxID_ANY, wxT("ScoutSim"), wxDefaultPosition,
69
                  wxSize(500, 500), wxDEFAULT_FRAME_STYLE & ~wxRESIZE_BORDER)
70
          , frame_count(0)
71
          , id_counter(0)
72
          , BOM_counter(0)
73
    {
74
        std::cout << "Constructing sim frame." << std::endl;
75

    
76
        srand(time(NULL));
77

    
78
        update_timer = new wxTimer(this);
79
        update_timer->Start(REAL_TIME_REFRESH_RATE * 1000);
80

    
81
        Connect(update_timer->GetId(), wxEVT_TIMER,
82
                wxTimerEventHandler(SimFrame::onUpdate), NULL, this);
83
        Connect(wxEVT_PAINT, wxPaintEventHandler(SimFrame::onPaint),
84
                NULL, this);
85

    
86
        images_path = ros::package::getPath("scoutsim") + "/images/";
87

    
88
        map_base_name =  ros::package::getPath("scoutsim") + "/maps/" +
89
                           map_name + ".bmp";
90
        map_lines_name = ros::package::getPath("scoutsim") + "/maps/" +
91
                           map_name + "_lines.bmp";
92
        map_walls_name = ros::package::getPath("scoutsim") + "/maps/" +
93
                           map_name + "_walls.bmp";
94
        display_map_name = map_base_name;
95

    
96
        wxBitmap lines_bitmap;
97
        wxBitmap walls_bitmap;
98
        ROS_INFO("Loading map: %s", display_map_name.c_str());
99
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
100

    
101
        // Try to load the file; if it fails, make a new blank file
102
        if (!lines_bitmap.LoadFile(wxString::FromAscii(map_lines_name.c_str())))
103
        {
104
            lines_bitmap = wxBitmap(path_bitmap.GetWidth(), path_bitmap.GetHeight(), 3);
105
        }
106
        lines_image = lines_bitmap.ConvertToImage();
107

    
108
        // Try to load the file; if it fails, make a new blank file
109
        if (!walls_bitmap.LoadFile(wxString::FromAscii(map_walls_name.c_str())))
110
        {
111
            walls_bitmap = wxBitmap(path_bitmap.GetWidth(), path_bitmap.GetHeight(), 3);
112
        }
113
        walls_image = walls_bitmap.ConvertToImage();
114

    
115
        clear();
116

    
117
        clear_srv = nh.advertiseService("clear",
118
                                        &SimFrame::clearCallback, this);
119
        reset_srv = nh.advertiseService("reset",
120
                                        &SimFrame::resetCallback, this);
121
        spawn_srv = nh.advertiseService("spawn",
122
                                        &SimFrame::spawnCallback, this);
123
        spawn_em_srv = nh.advertiseService("spawn_em",
124
                                        &SimFrame::spawnEmCallback, this);
125
        kill_srv = nh.advertiseService("kill",
126
                                        &SimFrame::killCallback, this);
127
        set_sonar_viz_srv = nh.advertiseService("set_sonar_viz",
128
                                        &SimFrame::setSonarVizCallback, this);
129
        set_ghost_srv = nh.advertiseService("set_ghost",
130
                                        &SimFrame::setGhostCallback, this);
131
        set_teleop_srv = nh.advertiseService("set_teleop",
132
                                        &SimFrame::setTeleopCallback, this);
133

    
134
        // Subscribe and publisher wirless from robots
135
        wireless_receive = nh.advertise< ::messages::WirelessPacket>(
136
            "/wireless/receive", 1000); 
137
        wireless_send = nh.subscribe("/wireless/send", 1000,
138
            &SimFrame::wirelessCallback, this);
139

    
140
        // Teleop
141
        teleop_type = TELEOP_OFF;
142
        teleop_l_speed = 0;
143
        teleop_r_speed = 0;
144
        teleop_scoutname = "scout1";
145

    
146
        //Emitter default values
147
        em_aperture = PI / 3.0;
148
        em_distance = 1.0;
149

    
150

    
151
        teleop_pub = nh.advertise< ::messages::set_motors>("/scout1/set_motors", 1000);
152

    
153
        ROS_INFO("Starting scoutsim with node name %s",
154
                 ros::this_node::getName().c_str()) ;
155

    
156
        wxMenu *menuFile = new wxMenu;
157
        menuFile->Append(ID_ABOUT, _("&About"));
158
        menuFile->AppendSeparator();
159
        menuFile->Append(ID_QUIT, _("E&xit"));
160

    
161
        wxMenu *menuSim = new wxMenu;
162
        menuSim->Append(ID_CLEAR, _("&Clear"));
163

    
164
        wxMenu *menuView = new wxMenu;
165
        menuView->Append(ID_MAP, _("&Map"));
166
        menuView->Append(ID_LINES, _("&Lines"));
167
        menuView->Append(ID_WALLS, _("&Walls"));
168

    
169
        wxMenu *menuTeleop = new wxMenu;
170
        menuTeleop->Append(ID_TELEOP_NONE, _("&None"));
171
        menuTeleop->Append(ID_TELEOP_PRECISE, _("&Precise"));
172
        menuTeleop->Append(ID_TELEOP_FLUID, _("&Fluid"));
173

    
174
        wxMenuBar *menuBar = new wxMenuBar;
175
        menuBar->Append(menuFile, _("&File"));
176
        menuBar->Append(menuSim, _("&Sim"));
177
        menuBar->Append(menuView, _("&View"));
178
        menuBar->Append(menuTeleop, _("&Teleop"));
179

    
180
        SetMenuBar(menuBar);
181

    
182
        width_in_meters = GetSize().GetWidth() / PIX_PER_METER;
183
        height_in_meters = GetSize().GetHeight() / PIX_PER_METER;
184

    
185
        spawnScout("scout1", 1.4, .78, 0);
186
    }
187

    
188
    SimFrame::~SimFrame()
189
    {
190
        delete update_timer;
191
    }
192

    
193
    bool SimFrame::spawnCallback(scoutsim::Spawn::Request  &req,
194
                                 scoutsim::Spawn::Response &res)
195
    {
196
        std::string name = spawnScout(req.name, req.x, req.y, req.theta);
197
        if (name.empty())
198
        {
199
            ROS_WARN("A scout named [%s] already exists", req.name.c_str());
200
            return false;
201
        }
202

    
203
        res.name = name;
204
        return true;
205
    }
206

    
207

    
208
    bool SimFrame::spawnEmCallback(scoutsim::Spawn::Request  &req,
209
                                 scoutsim::Spawn::Response &res)
210
    {
211
        std::string name = spawnEmitter(req.name, req.x, req.y, req.theta);
212
        if (name.empty())
213
        {
214
            ROS_WARN("An emitter named [%s] already exists", req.name.c_str());
215
            return false;
216
        }
217

    
218
        res.name = name;
219
        return true;
220
    }
221

    
222
    bool SimFrame::killCallback(scoutsim::Kill::Request& req,
223
                                scoutsim::Kill::Response&)
224
    {
225
        M_Scout::iterator it = scouts.find(req.name);
226
        M_Emitter::iterator m_it = emitters.find(req.name);
227
        if (it == scouts.end())
228
        {
229
            if (m_it == emitters.end()) {
230
                ROS_WARN("Tried to kill scout/emitter [%s], which does not exist",
231
                req.name.c_str());
232
                return false;
233
            }
234
            emitters.erase(m_it);
235
            return true;
236
        }
237

    
238
        scouts.erase(it);
239

    
240
        return true;
241
    }
242

    
243
    bool SimFrame::setSonarVizCallback(SetSonarViz::Request& req,
244
                                       SetSonarViz::Response&)
245
    {
246
        M_Scout::iterator it = scouts.find(req.scout_name);
247
        if (it == scouts.end())
248
        {
249
            ROS_WARN("Tried to set sonar on scout [%s], which does not exist",
250
                     req.scout_name.c_str());
251
            return false;
252
        }
253

    
254
        it->second->set_sonar_visual(req.on);
255
        return true;
256
    }
257

    
258
    bool SimFrame::setGhostCallback(SetGhost::Request& req,
259
                                    SetGhost::Response&)
260
    {
261
        for (unsigned int i=0; i < ghost_scouts.size(); ++i)
262
        {
263
            if (ghost_scouts.at(i)->get_name() == req.scout_name)
264
            {
265
                ghost_scouts.at(i)->set_visible(req.on);
266
                return true;
267
            }
268
        }
269

    
270
        ROS_WARN("Tried to set ghost on scout [%s], which does not exist",
271
                 req.scout_name.c_str());
272
        return false;
273
    }
274

    
275
    bool SimFrame::setTeleopCallback(SetTeleop::Request& req,
276
                                     SetTeleop::Response&)
277
    {
278
        std::stringstream ss;
279
        ss << "/" << req.scout_name << "/set_motors";
280
        teleop_pub = nh.advertise< ::messages::set_motors>(ss.str(), 1000);
281
        teleop_scoutname = req.scout_name.c_str();
282
        ROS_INFO("Teleoping %s...",teleop_scoutname.c_str()); //debug statement
283

    
284
        return true;
285
    }
286

    
287
    bool SimFrame::hasScout(const std::string& name)
288
    {
289
        return scouts.find(name) != scouts.end();
290
    }
291

    
292
    bool SimFrame::hasEmitter(const std::string& name)
293
    {
294
        return emitters.find(name) != emitters.end();
295
    }
296

    
297
    std::string SimFrame::spawnScout(const std::string& name,
298
                                     float x, float y, float angle)
299
    {
300
        std::string real_name = name;
301
        if (real_name.empty())
302
        {
303
            // Generate the name scoutX, where X is an increasing number.
304
            do
305
            {
306
                std::stringstream ss;
307
                ss << "scout" << ++id_counter;
308
                real_name = ss.str();
309
            }
310
            while (hasScout(real_name));
311
        }
312
        else
313
        {
314
            if (hasScout(real_name))
315
            {
316
                return "";
317
            }
318
        }
319

    
320
        wxImage scout_image;
321

    
322
        // Try to load a name-specific image; if not, load the default scout
323
        string specific_name = images_path + name + ".png";
324
        if (fileExists(specific_name))
325
        {
326
            scout_image.LoadFile(wxString::FromAscii(specific_name.c_str()));
327
            scout_image.SetMask(true);
328
            scout_image.SetMaskColour(255, 255, 255);
329
        }
330
        else
331
        {
332
            scout_image.LoadFile(
333
                wxString::FromAscii((images_path + "scout.png").c_str()));
334
            scout_image.SetMask(true);
335
            scout_image.SetMaskColour(255, 255, 255);
336
        }
337

    
338
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
339
                   scout_image, Vector2(x, y), &path_bitmap, angle));
340
        scouts[real_name] = t;
341

    
342
        ghost_scouts.push_back(new GhostScout(ros::NodeHandle(real_name),
343
                scout_image, Vector2(x, y), &path_bitmap, angle, name));
344

    
345
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
346
                 real_name.c_str(), x, y, angle);
347

    
348
        return real_name;
349
    }
350

    
351

    
352
    std::string SimFrame::spawnEmitter(const std::string& name,
353
                                     float x, float y, float angle)
354
    {
355
        std::string real_name = name;
356
        if (real_name.empty())
357
        {
358
            // Generate the name emitterX, where X is an increasing number.
359
            do
360
            {
361
                std::stringstream ss;
362
                ss << "emitter_" << ++BOM_counter;
363
                real_name = ss.str();
364
            }
365
            while (hasEmitter(real_name));
366
        }
367
        else
368
        {
369
            if (hasEmitter(real_name))
370
            {
371
                return "";
372
            }
373
        }
374

    
375
        wxImage emitter_image;
376

    
377
        // Try to load a name-specific image; if not, load the default emitter
378
        string specific_name = images_path + name + ".png";
379
        if (fileExists(specific_name))
380
        {
381
            emitter_image.LoadFile(wxString::FromAscii(specific_name.c_str()));
382
            emitter_image.SetMask(true);
383
            emitter_image.SetMaskColour(255, 255, 255);
384
        }
385
        else
386
        {
387
            ROS_INFO("LOADED EMITTER IMAGE");
388
            emitter_image.LoadFile(
389
                wxString::FromAscii((images_path + "emitter.png").c_str()));
390
            emitter_image.SetMask(true);
391
            emitter_image.SetMaskColour(255, 255, 255);
392
        }
393

    
394
        EmitterPtr t(new Emitter(ros::NodeHandle(real_name),
395
                   emitter_image, Vector2(x, y), &path_bitmap, 
396
                   angle, em_aperture, em_distance));
397
        emitters[real_name] = t;
398

    
399
        ROS_INFO("Spawning emitter [%s] at x=[%f], y=[%f], theta=[%f]",
400
                 real_name.c_str(), x, y, angle);
401

    
402
        return real_name;
403
    }
404

    
405

    
406
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
407
    {
408
        Close(true);
409
    }
410

    
411
    void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
412
    {
413
        wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
414
                       "\nThe Colony Project is a part of the Carnegie Mellon\n"
415
                       "Robotics Club. Our goal is to use cooperative low-cost\n"
416
                       "robots to solve challenging problems."),
417
                     _("About Scoutsim"),
418
                     wxOK | wxICON_INFORMATION, this );
419
    }
420

    
421
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
422
    {
423
        clear();
424
    }
425

    
426
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
427
    {
428
        display_map_name = map_base_name;
429
        clear();
430
    }
431

    
432
    void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
433
    {
434
        display_map_name = map_lines_name;
435
        clear();
436
    }
437
    
438
    void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
439
    {
440
        display_map_name = map_walls_name;
441
        clear();
442
    }
443

    
444
    void SimFrame::clear()
445
    {
446
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
447
        path_dc.Clear();
448

    
449
        sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0)));
450
        sonar_dc.Clear();
451

    
452
        sonar_dc.SelectObject(path_bitmap);
453

    
454
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
455
        path_dc.SelectObject(path_bitmap);
456
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
457
    }
458

    
459
    // Runs every REAL_TIME_REFRESH_RATE.
460
    void SimFrame::onUpdate(wxTimerEvent& evt)
461
    {
462
        ros::spinOnce();
463

    
464
        teleop();
465

    
466
        updateScouts();
467

    
468
        if (!ros::ok())
469
        {
470
            Close();
471
        }
472

    
473
        frame_count++;
474
    }
475

    
476
    void SimFrame::onPaint(wxPaintEvent& evt)
477
    {
478
        wxPaintDC dc(this);
479

    
480
        dc.DrawBitmap(path_bitmap, 0, 0, true);
481

    
482
        M_Scout::iterator it = scouts.begin();
483
        M_Scout::iterator end = scouts.end();
484
        for (; it != end; ++it)
485
        {
486
            it->second->paint(dc);
487
        }
488

    
489

    
490
        M_Emitter::iterator m_it = emitters.begin();
491
        M_Emitter::iterator m_end = emitters.end();
492
        for (; m_it != m_end; ++m_it)
493
        {
494
            m_it->second->paint(dc);
495
        }
496

    
497
        for (unsigned int i=0; i < ghost_scouts.size(); ++i)
498
        {
499
            ghost_scouts.at(i)->paint(dc);
500
        }
501
    }
502

    
503
    bool SimFrame::fileExists(const std::string& filename)
504
    {
505
        struct stat buf;
506
        if (stat(filename.c_str(), &buf) != -1)
507
        {
508
            return true;
509
        }
510
        return false;
511
    }
512

    
513
    void SimFrame::stopTeleop(wxCommandEvent& event)
514
    {
515
        teleop_type = TELEOP_OFF;
516
        teleop_l_speed = 0;
517
        teleop_r_speed = 0;
518
    }
519

    
520
    void SimFrame::startTeleopPrecise(wxCommandEvent& event)
521
    {
522
        teleop_type = TELEOP_PRECISE;
523
        teleop_l_speed = 0;
524
        teleop_r_speed = 0;
525
    }
526

    
527
    void SimFrame::startTeleopFluid(wxCommandEvent& event)
528
    {
529
        teleop_type = TELEOP_FLUID;
530
        teleop_l_speed = 0;
531
        teleop_r_speed = 0;
532
        teleop_fluid_speed = 0;
533
        teleop_fluid_omega = 0;
534
    }
535

    
536
    void SimFrame::teleop_move_precise()
537
    {
538
        // Default to stop
539
        teleop_l_speed = 0;
540
        teleop_r_speed = 0;
541

    
542
        if (wxGetKeyState(WXK_UP))
543
        {
544
            teleop_l_speed = TELEOP_PRECISE_SPEED;
545
            teleop_r_speed = TELEOP_PRECISE_SPEED;
546
        }
547
        else if (wxGetKeyState(WXK_DOWN))
548
        {
549
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
550
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
551
        }
552
        else if (wxGetKeyState(WXK_LEFT))
553
        {
554
            teleop_l_speed = -TELEOP_PRECISE_TURN_SPEED;
555
            teleop_r_speed = TELEOP_PRECISE_TURN_SPEED;
556
        }
557
        else if (wxGetKeyState(WXK_RIGHT))
558
        {
559
            teleop_l_speed = TELEOP_PRECISE_TURN_SPEED;
560
            teleop_r_speed = -TELEOP_PRECISE_TURN_SPEED;
561
        }
562
    }
563

    
564
    void SimFrame::teleop_move_fluid()
565
    {
566
        if (wxGetKeyState(WXK_UP))
567
        {
568
            teleop_fluid_speed += TELEOP_FLUID_INC * 2;
569
        }
570
        else if (wxGetKeyState(WXK_DOWN))
571
        {
572
            teleop_fluid_speed -= TELEOP_FLUID_INC * 2;
573
        }
574
        else if (teleop_fluid_speed > TELEOP_FLUID_INC)
575
        {
576
            teleop_fluid_speed -= TELEOP_FLUID_INC;
577
        }
578
        else if (teleop_fluid_speed < -TELEOP_FLUID_INC)
579
        {
580
            teleop_fluid_speed += TELEOP_FLUID_INC;
581
        }
582
        else
583
        {
584
            teleop_fluid_speed = 0;
585
        }
586

    
587
        if (wxGetKeyState(WXK_LEFT))
588
        {
589
            teleop_fluid_omega -= TELEOP_FLUID_INC * 2;
590
        }
591
        else if (wxGetKeyState(WXK_RIGHT))
592
        {
593
            teleop_fluid_omega += TELEOP_FLUID_INC * 2;
594
        }
595
        else
596
        {
597
            teleop_fluid_omega = 0;
598
        }
599

    
600
        if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
601
        {
602
            teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED;
603
        }
604
        else if (teleop_fluid_speed < -TELEOP_FLUID_MAX_SPEED)
605
        {
606
            teleop_fluid_speed = -TELEOP_FLUID_MAX_SPEED;
607
        }
608
        if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED)
609
        {
610
            teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED;
611
        }
612
        else if (teleop_fluid_omega < -TELEOP_FLUID_MAX_SPEED)
613
        {
614
            teleop_fluid_omega = -TELEOP_FLUID_MAX_SPEED;
615
        }
616

    
617
        int l_speed = teleop_fluid_speed + teleop_fluid_omega;
618
        int r_speed = teleop_fluid_speed - teleop_fluid_omega;
619

    
620
        teleop_l_speed = max(MIN_ABSOLUTE_SPEED,
621
                             min(MAX_ABSOLUTE_SPEED, l_speed));
622
        teleop_r_speed = max(MIN_ABSOLUTE_SPEED,
623
                             min(MAX_ABSOLUTE_SPEED, r_speed));
624
    }
625

    
626
    void SimFrame::teleop()
627
    {
628
        switch (teleop_type)
629
        {
630
            case TELEOP_OFF:
631
                return;
632
            case TELEOP_PRECISE:
633
                teleop_move_precise();
634
                break;
635
            case TELEOP_FLUID:
636
                teleop_move_fluid();
637
                break;
638
        }
639

    
640
        ::messages::set_motors msg;
641
        msg.fl_set = true;
642
        msg.fr_set = true;
643
        msg.bl_set = true;
644
        msg.br_set = true;
645
        msg.teleop_ON = true;
646

    
647
        msg.fl_speed = teleop_l_speed;
648
        msg.fr_speed = teleop_r_speed;
649
        msg.bl_speed = teleop_l_speed;
650
        msg.br_speed = teleop_r_speed;
651

    
652
        teleop_pub.publish(msg);
653
    }
654

    
655
    void SimFrame::updateScouts()
656
    {
657

    
658
        if (last_scout_update.isZero())
659
        {
660
            last_scout_update = ros::WallTime::now();
661
            return;
662
        }
663

    
664
        path_image = path_bitmap.ConvertToImage();
665
        Refresh();
666

    
667
        M_Scout::iterator it = scouts.begin();
668
        M_Scout::iterator end = scouts.end();
669

    
670
        M_Emitter::iterator m_it = emitters.begin();
671
        M_Emitter::iterator m_end = emitters.end();
672

    
673
        world_state state;
674
        state.canvas_width = width_in_meters;
675
        state.canvas_height = height_in_meters;
676

    
677

    
678
        for (; m_it != m_end; ++m_it)
679
        {
680

    
681
            m_it->second->update(SIM_TIME_REFRESH_RATE,
682
                               path_dc,
683
                               path_image, lines_image, walls_image,
684
                               path_dc.GetBackground().GetColour(),
685
                               state);
686
        }
687

    
688

    
689
        for (; it != end; ++it)
690
        {
691
            //ROS_INFO(it->second);
692
            geometry_msgs::Pose2D scout_pos;
693
            scout_pos = it->second->update(SIM_TIME_REFRESH_RATE,
694
                               path_dc, sonar_dc,
695
                               path_image, lines_image, walls_image,
696
                               path_dc.GetBackground().GetColour(),
697
                               sonar_dc.GetBackground().GetColour(),
698
                               state);
699

    
700
            checkBOM(scout_pos, it);            
701
        }
702

    
703

    
704
        for (unsigned int i = 0; i < ghost_scouts.size(); ++i)
705
        {
706
            ghost_scouts.at(i)->update(SIM_TIME_REFRESH_RATE, path_dc, sonar_dc,
707
                path_dc.GetBackground().GetColour(), state);
708
        }
709

    
710

    
711
        frame_count++;
712
    }
713

    
714

    
715
    void SimFrame::checkBOM(geometry_msgs::Pose2D scout_pos, 
716
                            M_Scout::iterator it)
717
     {
718

    
719
        M_Emitter::iterator m_it = emitters.begin();
720
        M_Emitter::iterator m_end = emitters.end();
721

    
722
        //Emitter default values
723
        double bom_aperture = PI / 3.0;
724
        double bom_distance = 1.0;
725
    
726
            //iterate over Emitters:
727
       for (; m_it != m_end; ++m_it)
728
        {
729
            geometry_msgs::Pose2D emitter_pos;
730
            emitter_pos = m_it->second->get_pos();
731
            if (is_inrange(scout_pos, emitter_pos, em_aperture, em_distance)) { 
732
            //if scout is within emitter range
733
            //check if emitter is within each BOM range
734
            double x_offset;
735
            double y_offset;    
736
            double offset_angle;
737
            double diag_dis = pow((pow((SCOUT_W/2.0),2) + 
738
                              pow((SCOUT_H/2.0),2)),(0.5));
739

    
740
                for (int i = 0; i<10; i++) {
741
                geometry_msgs::Pose2D bom_pos;
742
                
743
                if (i == 2) { //middle left
744
                    offset_angle = PI/2.0;
745
                    bom_pos.theta = scout_pos.theta + PI/2.0;
746
                }
747
                else if (i == 7) { //middle right
748
                    offset_angle = 3*PI/2.0;
749
                    bom_pos.theta = scout_pos.theta + 3.0*PI/2.0;
750
                }
751
                else if (i < 2) { //top left
752
                    offset_angle =  atan(abs((SCOUT_W/2.0)/(SCOUT_H/2.0)));
753
                    bom_pos.theta = scout_pos.theta + PI/2.0 * i;
754
                }
755
                else if (i >= 2 && i <5) { //bottom left
756
                    offset_angle =  PI - atan(abs((SCOUT_W/2.0)/(SCOUT_H/2.0)));
757
                    bom_pos.theta = scout_pos.theta + PI/2.0 + PI/2.0 * (i/4);
758
                }
759
                else if (i >= 5 && i < 8) { //bottom right
760
                    offset_angle =  PI + atan(abs((SCOUT_W/2.0)/(SCOUT_H/2.0)));
761
                    bom_pos.theta = scout_pos.theta + PI + PI/2.0 * (i/6);
762
                }
763
                else { //top right
764
                    offset_angle =  2*PI - atan(abs((SCOUT_W/2.0)/(SCOUT_H/2.0)));
765
                    bom_pos.theta = scout_pos.theta + 3*PI/2.0 + PI/2.0 * (i/9);
766
                }
767
                offset_angle += scout_pos.theta;
768
                
769
                if (i == 2 || i == 7) {
770
                    x_offset = (SCOUT_W/2.0)*cos(offset_angle);
771
                    y_offset = (SCOUT_W/2.0)*sin(offset_angle);
772
                }
773
                else {
774
                    x_offset = diag_dis*cos(offset_angle);
775
                    y_offset = diag_dis*sin(offset_angle);
776
                }
777

    
778
                bom_pos.x = scout_pos.x + x_offset;
779
                bom_pos.y = scout_pos.y - y_offset;  
780

    
781
                if (bom_pos.theta > 2*PI) {
782
                    bom_pos.theta -= 2*PI;
783
                }  
784
                else if (bom_pos.theta < 0) {
785
                    bom_pos.theta += 2*PI;
786
                }
787

    
788
                if(is_inrange(emitter_pos, bom_pos, bom_aperture, bom_distance)) {
789
                    string em_id_str = it->first.substr(it->first.find("_"));
790
                    int emitter_id = atoi(em_id_str.c_str());
791
                    it->second->update_BOM(i, 1, emitter_id);
792
                }
793
                else {
794
                    it->second->update_BOM(i, 0, 0);
795
                }
796
                }
797
            }
798
        }
799

    
800
    }
801

    
802

    
803
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
804
                                 std_srvs::Empty::Response&)
805
    {
806
        ROS_INFO("Clearing scoutsim.");
807
        clear();
808
        return true;
809
    }
810

    
811
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
812
                                 std_srvs::Empty::Response&)
813
    {
814
        ROS_INFO("Resetting scoutsim.");
815
        scouts.clear();
816
        id_counter = 0;
817
        BOM_counter = 0;
818

    
819
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
820
        clear();
821
        return true;
822
    }
823

    
824
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
825
    {
826
        wireless_receive.publish(msg);
827
    }
828

    
829

    
830
    bool SimFrame::is_inrange(geometry_msgs::Pose2D scout_pos,
831
                           geometry_msgs::Pose2D emitter_pos,
832
                           double aperture, double distance)
833
                           
834
    {
835
        //ROS_INFO("SCOUT: %f %f %f ", scout_pos.x, scout_pos.x, scout_pos.theta);
836
        //ROS_INFO("EMITTER: %f %f %f ", emitter_pos.x, emitter_pos.x, emitter_pos.theta);
837
        double se_distance = pow((pow((scout_pos.x - emitter_pos.x),2) + 
838
                              pow((scout_pos.y - emitter_pos.y),2)),(0.5));
839
        double se_angle = atan((scout_pos.x - emitter_pos.x)/(scout_pos.y - emitter_pos.y));
840
        if (scout_pos.y < emitter_pos.y)
841
        {
842
            se_angle = se_angle + PI/2;
843
        }        
844
        else 
845
        {
846
            se_angle = se_angle + PI*3/2;
847
        }
848
        double emitter_orient = emitter_pos.theta;
849
        
850
        //ROS_INFO("distance: %f, angle: %f, orient: %f", se_distance, se_angle, emitter_orient);
851

    
852
        if ((se_distance <= distance)) { //distance check
853

    
854
            double upper_limit = (emitter_orient + aperture/2);
855
            double lower_limit = (emitter_orient - aperture/2);
856

    
857
            //ROS_INFO("upper: %f, lower: %f", upper_limit, lower_limit+2*PI);
858

    
859
            if (upper_limit > 2*PI) {
860
               if (((se_angle < 2*PI) && (se_angle > (lower_limit))) ||
861
                   ((se_angle < upper_limit-2*PI) && (se_angle >= 0))) {
862
                return true;
863
                }
864
                
865
            }
866
            else if (lower_limit < 0) {
867
                if (((se_angle < 2*PI) && (se_angle > (lower_limit+2*PI))) ||
868
                   ((se_angle < upper_limit) && (se_angle >= 0))) {
869
                return true;
870
                }
871

    
872

    
873
            }
874
            else {
875
                if ((se_angle < upper_limit) && //angle check 
876
                    (se_angle > lower_limit)) {
877
                return true;
878
                }   
879
            }
880
        }
881
        return false;
882
            
883
    }
884

    
885
}
886

    
887
/** @} */