Project

General

Profile

Statistics
| Branch: | Revision:

robobuggy / scoutos / scout / scoutsim / src / sim_frame.cpp @ 8e58dd0e

History | View | Annotate | Download (28 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
        // Maps are stored in three components:
86
        //   - images : the top layer
87
        //   - lines : for the line-following sensor
88
        //   - walls : for the...clamping?
89
        images_path = ros::package::getPath("scoutsim") + "/images/";
90

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

    
99
        wxBitmap lines_bitmap;
100
        wxBitmap walls_bitmap;
101
        ROS_INFO("Loading map: %s", display_map_name.c_str());
102
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
103

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

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

    
118
        clear();
119

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

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

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

    
149
        //Emitter default values
150
        em_aperture = PI / 3.0;
151
        em_distance = 1.0;
152

    
153

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

    
156
        ROS_INFO("Starting scoutsim with node name %s",
157
                 ros::this_node::getName().c_str()) ;
158

    
159
        wxMenu *menuFile = new wxMenu;
160
        menuFile->Append(ID_ABOUT, _("&About"));
161
        menuFile->AppendSeparator();
162
        menuFile->Append(ID_QUIT, _("E&xit"));
163

    
164
        wxMenu *menuSim = new wxMenu;
165
        menuSim->Append(ID_CLEAR, _("&Clear"));
166

    
167
        wxMenu *menuView = new wxMenu;
168
        menuView->Append(ID_MAP, _("&Map"));
169
        menuView->Append(ID_LINES, _("&Lines"));
170
        menuView->Append(ID_WALLS, _("&Walls"));
171

    
172
        wxMenu *menuTeleop = new wxMenu;
173
        menuTeleop->Append(ID_TELEOP_NONE, _("&None"));
174
        menuTeleop->Append(ID_TELEOP_PRECISE, _("&Precise"));
175
        menuTeleop->Append(ID_TELEOP_FLUID, _("&Fluid"));
176

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

    
183
        SetMenuBar(menuBar);
184

    
185
        width_in_meters = GetSize().GetWidth() / PIX_PER_METER;
186
        height_in_meters = GetSize().GetHeight() / PIX_PER_METER;
187

    
188
        spawnScout("scout1", 1.4, .78, 0);
189
    }
190

    
191
    SimFrame::~SimFrame()
192
    {
193
        delete update_timer;
194
    }
195

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

    
206
        res.name = name;
207
        return true;
208
    }
209

    
210

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

    
221
        res.name = name;
222
        return true;
223
    }
224

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

    
241
        scouts.erase(it);
242

    
243
        return true;
244
    }
245

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

    
257
        it->second->set_sonar_visual(req.on);
258
        return true;
259
    }
260

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

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

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

    
287
        return true;
288
    }
289

    
290
    bool SimFrame::hasScout(const std::string& name)
291
    {
292
        return scouts.find(name) != scouts.end();
293
    }
294

    
295
    bool SimFrame::hasEmitter(const std::string& name)
296
    {
297
        return emitters.find(name) != emitters.end();
298
    }
299

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

    
323
        wxImage scout_image;
324

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

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

    
345
        ghost_scouts.push_back(new GhostScout(ros::NodeHandle(real_name),
346
                scout_image, Vector2(x, y), &path_bitmap, angle, name));
347

    
348
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
349
                 real_name.c_str(), x, y, angle);
350

    
351
        return real_name;
352
    }
353

    
354

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

    
378
        wxImage emitter_image;
379

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

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

    
402
        ROS_INFO("Spawning emitter [%s] at x=[%f], y=[%f], theta=[%f]",
403
                 real_name.c_str(), x, y, angle);
404

    
405
        return real_name;
406
    }
407

    
408

    
409
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
410
    {
411
        Close(true);
412
    }
413

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

    
424
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
425
    {
426
        clear();
427
    }
428

    
429
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
430
    {
431
        display_map_name = map_base_name;
432
        clear();
433
    }
434

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

    
447
    void SimFrame::clear()
448
    {
449
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
450
        path_dc.Clear();
451

    
452
        sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0)));
453
        sonar_dc.Clear();
454

    
455
        sonar_dc.SelectObject(path_bitmap);
456

    
457
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
458
        path_dc.SelectObject(path_bitmap);
459
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
460
    }
461

    
462
    // Runs every REAL_TIME_REFRESH_RATE.
463
    void SimFrame::onUpdate(wxTimerEvent& evt)
464
    {
465
        ros::spinOnce();
466

    
467
        teleop();
468

    
469
        updateScouts();
470

    
471
        if (!ros::ok())
472
        {
473
            Close();
474
        }
475

    
476
        frame_count++;
477
    }
478

    
479
    void SimFrame::onPaint(wxPaintEvent& evt)
480
    {
481
        wxPaintDC dc(this);
482

    
483
        dc.DrawBitmap(path_bitmap, 0, 0, true);
484

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

    
492

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

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

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

    
516
    void SimFrame::stopTeleop(wxCommandEvent& event)
517
    {
518
        teleop_type = TELEOP_OFF;
519
        teleop_l_speed = 0;
520
        teleop_r_speed = 0;
521
    }
522

    
523
    void SimFrame::startTeleopPrecise(wxCommandEvent& event)
524
    {
525
        teleop_type = TELEOP_PRECISE;
526
        teleop_l_speed = 0;
527
        teleop_r_speed = 0;
528
    }
529

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

    
539
    void SimFrame::teleop_move_precise()
540
    {
541
        // Default to stop
542
        teleop_l_speed = 0;
543
        teleop_r_speed = 0;
544

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

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

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

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

    
620
        int l_speed = teleop_fluid_speed + teleop_fluid_omega;
621
        int r_speed = teleop_fluid_speed - teleop_fluid_omega;
622

    
623
        teleop_l_speed = max(MIN_ABSOLUTE_SPEED,
624
                             min(MAX_ABSOLUTE_SPEED, l_speed));
625
        teleop_r_speed = max(MIN_ABSOLUTE_SPEED,
626
                             min(MAX_ABSOLUTE_SPEED, r_speed));
627
    }
628

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

    
643
        ::messages::set_motors msg;
644
        msg.fl_set = true;
645
        msg.fr_set = true;
646
        msg.bl_set = true;
647
        msg.br_set = true;
648
        msg.teleop_ON = true;
649

    
650
        msg.fl_speed = teleop_l_speed;
651
        msg.fr_speed = teleop_r_speed;
652
        msg.bl_speed = teleop_l_speed;
653
        msg.br_speed = teleop_r_speed;
654

    
655
        teleop_pub.publish(msg);
656
    }
657

    
658
    void SimFrame::updateScouts()
659
    {
660

    
661
        if (last_scout_update.isZero())
662
        {
663
            last_scout_update = ros::WallTime::now();
664
            return;
665
        }
666

    
667
        path_image = path_bitmap.ConvertToImage();
668
        Refresh();
669

    
670
        M_Scout::iterator it = scouts.begin();
671
        M_Scout::iterator end = scouts.end();
672

    
673
        M_Emitter::iterator m_it = emitters.begin();
674
        M_Emitter::iterator m_end = emitters.end();
675

    
676
        world_state state;
677
        state.canvas_width = width_in_meters;
678
        state.canvas_height = height_in_meters;
679

    
680

    
681
        for (; m_it != m_end; ++m_it)
682
        {
683

    
684
            m_it->second->update(SIM_TIME_REFRESH_RATE,
685
                               path_dc,
686
                               path_image, lines_image, walls_image,
687
                               path_dc.GetBackground().GetColour(),
688
                               state);
689
        }
690

    
691

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

    
703
            checkBOM(scout_pos, it);            
704
        }
705

    
706

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

    
713

    
714
        frame_count++;
715
    }
716

    
717

    
718
    void SimFrame::checkBOM(geometry_msgs::Pose2D scout_pos, 
719
                            M_Scout::iterator it)
720
     {
721

    
722
        M_Emitter::iterator m_it = emitters.begin();
723
        M_Emitter::iterator m_end = emitters.end();
724

    
725
        //Emitter default values
726
        double bom_aperture = PI / 3.0;
727
        double bom_distance = 1.0;
728
    
729
            //iterate over Emitters:
730
       for (; m_it != m_end; ++m_it)
731
        {
732
            geometry_msgs::Pose2D emitter_pos;
733
            emitter_pos = m_it->second->get_pos();
734
            if (is_inrange(scout_pos, emitter_pos, em_aperture, em_distance)) { 
735
            //if scout is within emitter range
736
            //check if emitter is within each BOM range
737
            double x_offset;
738
            double y_offset;    
739
            double offset_angle;
740
            double diag_dis = pow((pow((SCOUT_W/2.0),2) + 
741
                              pow((SCOUT_H/2.0),2)),(0.5));   
742
                    
743
                for (int i = 0; i<10; i++) {
744
                geometry_msgs::Pose2D bom_pos;
745
                
746
                if (i == 2) { //middle left
747
                    offset_angle = PI/2.0;
748
                    bom_pos.theta = scout_pos.theta + PI/2.0;
749
                }
750
                else if (i == 7) { //middle right
751
                    offset_angle = 3*PI/2.0;
752
                    bom_pos.theta = scout_pos.theta + 3.0*PI/2.0;
753
                }
754
                else if (i < 2) { //top left
755
                    offset_angle =  atan(abs((SCOUT_W/2.0)/(SCOUT_H/2.0)));
756
                    bom_pos.theta = scout_pos.theta + PI/2.0 * i;
757
                }
758
                else if (i >= 2 && i <5) { //bottom left
759
                    offset_angle =  PI - atan(abs((SCOUT_W/2.0)/(SCOUT_H/2.0)));
760
                    bom_pos.theta = scout_pos.theta + PI/2.0 + PI/2.0 * (i/4);
761
                }
762
                else if (i >= 5 && i < 8) { //bottom right
763
                    offset_angle =  PI + atan(abs((SCOUT_W/2.0)/(SCOUT_H/2.0)));
764
                    bom_pos.theta = scout_pos.theta + PI + PI/2.0 * (i/6);
765
                }
766
                else { //top right
767
                    offset_angle =  2*PI - atan(abs((SCOUT_W/2.0)/(SCOUT_H/2.0)));
768
                    bom_pos.theta = scout_pos.theta + 3*PI/2.0 + PI/2.0 * (i/9);
769
                }
770
                offset_angle += scout_pos.theta;
771
                
772
                if (i == 2 || i == 7) {
773
                    x_offset = (SCOUT_W/2.0)*cos(offset_angle);
774
                    y_offset = (SCOUT_W/2.0)*sin(offset_angle);
775
                }
776
                else {
777
                    x_offset = diag_dis*cos(offset_angle);
778
                    y_offset = diag_dis*sin(offset_angle);
779
                }
780

    
781
                bom_pos.x = scout_pos.x + x_offset;
782
                bom_pos.y = scout_pos.y - y_offset;  
783

    
784
                if (bom_pos.theta > 2*PI) {
785
                    bom_pos.theta -= 2*PI;
786
                }  
787
                else if (bom_pos.theta < 0) {
788
                    bom_pos.theta += 2*PI;
789
                }
790

    
791
                if(is_inrange(emitter_pos, bom_pos, bom_aperture, bom_distance)) {
792
                        
793
                        it->second->update_BOM(i, 1, 0);
794
                            // TODO: change to last arg to actual sender ID
795
                        
796
                    }
797
                else {
798
                        
799
                        it->second->update_BOM(i, 0, 0);
800
                            // TODO: change to last arg to actual sender ID
801
                        
802
                }
803
                }
804
                
805
            }
806
        }
807

    
808
    }
809

    
810

    
811
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
812
                                 std_srvs::Empty::Response&)
813
    {
814
        ROS_INFO("Clearing scoutsim.");
815
        clear();
816
        return true;
817
    }
818

    
819
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
820
                                 std_srvs::Empty::Response&)
821
    {
822
        ROS_INFO("Resetting scoutsim.");
823
        scouts.clear();
824
        id_counter = 0;
825
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
826
        clear();
827
        return true;
828
    }
829

    
830
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
831
    {
832
        wireless_receive.publish(msg);
833
    }
834

    
835

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

    
858
        if ((se_distance <= distance)) { //distance check
859

    
860
            double upper_limit = (emitter_orient + aperture/2);
861
            double lower_limit = (emitter_orient - aperture/2);
862

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

    
865
            if (upper_limit > 2*PI) {
866
               if (((se_angle < 2*PI) && (se_angle > (lower_limit))) ||
867
                   ((se_angle < upper_limit-2*PI) && (se_angle >= 0))) {
868
                return true;
869
                }
870
                
871
            }
872
            else if (lower_limit < 0) {
873
                if (((se_angle < 2*PI) && (se_angle > (lower_limit+2*PI))) ||
874
                   ((se_angle < upper_limit) && (se_angle >= 0))) {
875
                return true;
876
                }
877

    
878

    
879
            }
880
            else {
881
                if ((se_angle < upper_limit) && //angle check 
882
                    (se_angle > lower_limit)) {
883
                return true;
884
                }   
885
            }
886
        }
887
        return false;
888
            
889
    }
890

    
891
}
892

    
893
/** @} */