Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / sim_frame.cpp @ 98ed4757

History | View | Annotate | Download (24.6 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
    {
73
        std::cout << "Constructing sim frame." << std::endl;
74

    
75
        srand(time(NULL));
76

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

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

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

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

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

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

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

    
114
        clear();
115

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

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

    
139
        //Emitter default values
140
        em_aperture = PI / 3.0;
141
        em_distance = 1;
142

    
143

    
144
        // Teleop
145
        teleop_type = TELEOP_OFF;
146
        teleop_l_speed = 0;
147
        teleop_r_speed = 0;
148
        teleop_scoutname = "scout1";
149

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

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

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

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

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

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

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

    
179
        SetMenuBar(menuBar);
180

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

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

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

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

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

    
206

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

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

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

    
237
        scouts.erase(it);
238

    
239
        return true;
240
    }
241

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

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

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

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

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

    
283
        return true;
284
    }
285

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

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

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

    
319
        wxImage scout_image;
320

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

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

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

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

    
347
        return real_name;
348
    }
349

    
350

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

    
374
        wxImage emitter_image;
375

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

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

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

    
401
        return real_name;
402
    }
403

    
404

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

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

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

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

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

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

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

    
451
        sonar_dc.SelectObject(path_bitmap);
452

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

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

    
463
        teleop();
464

    
465
        updateScouts();
466

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

    
472
        frame_count++;
473
    }
474

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

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

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

    
488

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

    
651
        teleop_pub.publish(msg);
652
    }
653

    
654
    void SimFrame::updateScouts()
655
    {
656

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

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

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

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

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

    
676
        for (; m_it != m_end; ++m_it)
677
        {
678

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

    
686

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

    
698
            //iterate over Emitters:
699
           for (m_it = emitters.begin(); m_it != m_end; ++m_it)
700
            {
701
                geometry_msgs::Pose2D emitter_pos;
702
                emitter_pos = m_it->second->get_pos();
703
                readBOM(scout_pos, emitter_pos,it);
704
            }
705
            
706
        }
707

    
708

    
709
        for (unsigned int i = 0; i < ghost_scouts.size(); ++i)
710
        {
711
            ghost_scouts.at(i)->update(SIM_TIME_REFRESH_RATE, path_dc, sonar_dc,
712
                path_dc.GetBackground().GetColour(), state);
713
        }
714

    
715

    
716
        frame_count++;
717
    }
718

    
719

    
720
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
721
                                 std_srvs::Empty::Response&)
722
    {
723
        ROS_INFO("Clearing scoutsim.");
724
        clear();
725
        return true;
726
    }
727

    
728
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
729
                                 std_srvs::Empty::Response&)
730
    {
731
        ROS_INFO("Resetting scoutsim.");
732
        scouts.clear();
733
        id_counter = 0;
734
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
735
        clear();
736
        return true;
737
    }
738

    
739
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
740
    {
741
        wireless_receive.publish(msg);
742
    }
743

    
744

    
745
    void SimFrame::readBOM(geometry_msgs::Pose2D scout_pos,
746
                           geometry_msgs::Pose2D emitter_pos,
747
                           M_Scout::iterator it)
748
    {
749
        //ROS_INFO("SCOUT: %f %f %f ", scout_pos.x, scout_pos.x, scout_pos.theta);
750
        //ROS_INFO("EMITTER: %f %f %f ", emitter_pos.x, emitter_pos.x, emitter_pos.theta);
751
        double se_distance = pow((pow((scout_pos.x - emitter_pos.x),2) + 
752
                              pow((scout_pos.y - emitter_pos.y),2)),(0.5));
753
        double se_angle = atan((scout_pos.x - emitter_pos.x)/(scout_pos.y - emitter_pos.y));
754
        if (scout_pos.y < emitter_pos.y)
755
        {
756
            se_angle = se_angle + PI/2;
757
        }        
758
        else 
759
        {
760
            se_angle = se_angle + PI*3/2;
761
        }
762
        double emitter_orient = emitter_pos.theta;
763
        
764
        //ROS_INFO("distance: %f, angle: %f, orient: %f", se_distance, se_angle, emitter_orient);
765

    
766
        if ((se_distance <= em_distance)) { //distance check
767

    
768
            double upper_limit = (emitter_orient + em_aperture/2);
769
            double lower_limit = (emitter_orient - em_aperture/2);
770

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

    
773
            if (upper_limit > 2*PI) {
774
               if (((se_angle < 2*PI) && (se_angle > (lower_limit))) ||
775
                   ((se_angle < upper_limit-2*PI) && (se_angle >= 0))) {
776
                it->second->pub_BOM(true);
777
                }
778
                
779
            }
780
            else if (lower_limit < 0) {
781
                if (((se_angle < 2*PI) && (se_angle > (lower_limit+2*PI))) ||
782
                   ((se_angle < upper_limit) && (se_angle >= 0))) {
783
                it->second->pub_BOM(true);
784
                }
785

    
786

    
787
            }
788
            else {
789
                if ((se_angle < upper_limit) && //angle check 
790
                    (se_angle > lower_limit)) {
791
                it->second->pub_BOM(true);      
792
                }   
793
            }
794
        }
795
            
796
    }
797

    
798
}
799

    
800
/** @} */