Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / sim_frame.cpp @ 4c9fb6ba

History | View | Annotate | Download (18.9 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
#include "sim_frame.h"
49

    
50
#include <stdio.h>
51

    
52
#include <ros/package.h>
53
#include <cstdlib>
54
#include <ctime>
55

    
56
using namespace std;
57

    
58
namespace scoutsim
59
{
60
    SimFrame::SimFrame(wxWindow* parent, string map_name)
61
        : wxFrame(parent, wxID_ANY, wxT("ScoutSim"), wxDefaultPosition,
62
                  wxSize(500, 500), wxDEFAULT_FRAME_STYLE & ~wxRESIZE_BORDER)
63
          , frame_count(0)
64
          , id_counter(0)
65
    {
66
        std::cout << "Constructing sim frame." << std::endl;
67

    
68
        srand(time(NULL));
69

    
70
        update_timer = new wxTimer(this);
71
        update_timer->Start(REAL_TIME_REFRESH_RATE * 1000);
72

    
73
        Connect(update_timer->GetId(), wxEVT_TIMER,
74
                wxTimerEventHandler(SimFrame::onUpdate), NULL, this);
75
        Connect(wxEVT_PAINT, wxPaintEventHandler(SimFrame::onPaint),
76
                NULL, this);
77

    
78
        images_path = ros::package::getPath("scoutsim") + "/images/";
79

    
80
        map_base_name =  ros::package::getPath("scoutsim") + "/maps/" +
81
                           map_name + ".bmp";
82
        map_lines_name = ros::package::getPath("scoutsim") + "/maps/" +
83
                           map_name + "_lines.bmp";
84
        map_walls_name = ros::package::getPath("scoutsim") + "/maps/" +
85
                           map_name + "_walls.bmp";
86
        display_map_name = map_base_name;
87

    
88
        wxBitmap lines_bitmap;
89
        wxBitmap walls_bitmap;
90
        ROS_INFO("Loading map: %s", display_map_name.c_str());
91
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
92

    
93
        // Try to load the file; if it fails, make a new blank file
94
        if (!lines_bitmap.LoadFile(wxString::FromAscii(map_lines_name.c_str())))
95
        {
96
            lines_bitmap = wxBitmap(path_bitmap.GetWidth(), path_bitmap.GetHeight(), 3);
97
        }
98
        lines_image = lines_bitmap.ConvertToImage();
99

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

    
107
        clear();
108

    
109
        clear_srv = nh.advertiseService("clear",
110
                                        &SimFrame::clearCallback, this);
111
        reset_srv = nh.advertiseService("reset",
112
                                        &SimFrame::resetCallback, this);
113
        spawn_srv = nh.advertiseService("spawn",
114
                                        &SimFrame::spawnCallback, this);
115
        kill_srv = nh.advertiseService("kill",
116
                                        &SimFrame::killCallback, this);
117
        set_sonar_viz_srv = nh.advertiseService("set_sonar_viz",
118
                                        &SimFrame::setSonarVizCallback, this);
119
        set_ghost_srv = nh.advertiseService("set_ghost",
120
                                        &SimFrame::setGhostCallback, this);
121
        set_teleop_srv = nh.advertiseService("set_teleop",
122
                                        &SimFrame::setTeleopCallback, this);
123

    
124
        // Subscribe and publisher wirless from robots
125
        wireless_receive = nh.advertise< ::messages::WirelessPacket>(
126
            "/wireless/receive", 1000); 
127
        wireless_send = nh.subscribe("/wireless/send", 1000,
128
            &SimFrame::wirelessCallback, this);
129

    
130
        // Teleop
131
        teleop_type = TELEOP_OFF;
132
        teleop_l_speed = 0;
133
        teleop_r_speed = 0;
134
        teleop_scoutname = "scout1";
135

    
136
        teleop_pub = nh.advertise<motors::set_motors>("/scout1/set_motors", 1000);
137

    
138
        ROS_INFO("Starting scoutsim with node name %s",
139
                 ros::this_node::getName().c_str()) ;
140

    
141
        wxMenu *menuFile = new wxMenu;
142
        menuFile->Append(ID_ABOUT, _("&About"));
143
        menuFile->AppendSeparator();
144
        menuFile->Append(ID_QUIT, _("E&xit"));
145

    
146
        wxMenu *menuSim = new wxMenu;
147
        menuSim->Append(ID_CLEAR, _("&Clear"));
148

    
149
        wxMenu *menuView = new wxMenu;
150
        menuView->Append(ID_MAP, _("&Map"));
151
        menuView->Append(ID_LINES, _("&Lines"));
152
        menuView->Append(ID_WALLS, _("&Walls"));
153

    
154
        wxMenu *menuTeleop = new wxMenu;
155
        menuTeleop->Append(ID_TELEOP_NONE, _("&None"));
156
        menuTeleop->Append(ID_TELEOP_PRECISE, _("&Precise"));
157
        menuTeleop->Append(ID_TELEOP_FLUID, _("&Fluid"));
158

    
159
        wxMenuBar *menuBar = new wxMenuBar;
160
        menuBar->Append(menuFile, _("&File"));
161
        menuBar->Append(menuSim, _("&Sim"));
162
        menuBar->Append(menuView, _("&View"));
163
        menuBar->Append(menuTeleop, _("&Teleop"));
164

    
165
        SetMenuBar(menuBar);
166

    
167
        width_in_meters = GetSize().GetWidth() / PIX_PER_METER;
168
        height_in_meters = GetSize().GetHeight() / PIX_PER_METER;
169

    
170
        spawnScout("scout1", 1.4, .78, 0);
171
    }
172

    
173
    SimFrame::~SimFrame()
174
    {
175
        delete update_timer;
176
    }
177

    
178
    bool SimFrame::spawnCallback(scoutsim::Spawn::Request  &req,
179
                                 scoutsim::Spawn::Response &res)
180
    {
181
        std::string name = spawnScout(req.name, req.x, req.y, req.theta);
182
        if (name.empty())
183
        {
184
            ROS_WARN("A scout named [%s] already exists", req.name.c_str());
185
            return false;
186
        }
187

    
188
        res.name = name;
189
        return true;
190
    }
191

    
192
    bool SimFrame::killCallback(scoutsim::Kill::Request& req,
193
                                scoutsim::Kill::Response&)
194
    {
195
        M_Scout::iterator it = scouts.find(req.name);
196
        if (it == scouts.end())
197
        {
198
            ROS_WARN("Tried to kill scout [%s], which does not exist",
199
                     req.name.c_str());
200
            return false;
201
        }
202

    
203
        scouts.erase(it);
204

    
205
        return true;
206
    }
207

    
208
    bool SimFrame::setSonarVizCallback(SetSonarViz::Request& req,
209
                                       SetSonarViz::Response&)
210
    {
211
        M_Scout::iterator it = scouts.find(req.scout_name);
212
        if (it == scouts.end())
213
        {
214
            ROS_WARN("Tried to set sonar on scout [%s], which does not exist",
215
                     req.scout_name.c_str());
216
            return false;
217
        }
218

    
219
        it->second->set_sonar_visual(req.on);
220
        return true;
221
    }
222

    
223
    bool SimFrame::setGhostCallback(SetGhost::Request& req,
224
                                    SetGhost::Response&)
225
    {
226
        for (unsigned int i=0; i < ghost_scouts.size(); ++i)
227
        {
228
            if (ghost_scouts.at(i)->get_name() == req.scout_name)
229
            {
230
                ghost_scouts.at(i)->set_visible(req.on);
231
                return true;
232
            }
233
        }
234

    
235
        ROS_WARN("Tried to set ghost on scout [%s], which does not exist",
236
                 req.scout_name.c_str());
237
        return false;
238
    }
239

    
240
    bool SimFrame::setTeleopCallback(SetTeleop::Request& req,
241
                                     SetTeleop::Response&)
242
    {
243
        std::stringstream ss;
244
        ss << "/" << req.scout_name << "/set_motors";
245
        teleop_pub = nh.advertise<motors::set_motors>(ss.str(), 1000);
246
        teleop_scoutname = req.scout_name.c_str();
247
        ROS_INFO("Teleoping %s...",teleop_scoutname.c_str()); //debug statement
248

    
249
        return true;
250
    }
251

    
252
    bool SimFrame::hasScout(const std::string& name)
253
    {
254
        return scouts.find(name) != scouts.end();
255
    }
256

    
257
    std::string SimFrame::spawnScout(const std::string& name,
258
                                     float x, float y, float angle)
259
    {
260
        std::string real_name = name;
261
        if (real_name.empty())
262
        {
263
            // Generate the name scoutX, where X is an increasing number.
264
            do
265
            {
266
                std::stringstream ss;
267
                ss << "scout" << ++id_counter;
268
                real_name = ss.str();
269
            }
270
            while (hasScout(real_name));
271
        }
272
        else
273
        {
274
            if (hasScout(real_name))
275
            {
276
                return "";
277
            }
278
        }
279

    
280
        wxImage scout_image;
281

    
282
        // Try to load a name-specific image; if not, load the default scout
283
        string specific_name = images_path + name + ".png";
284
        if (fileExists(specific_name))
285
        {
286
            scout_image.LoadFile(wxString::FromAscii(specific_name.c_str()));
287
            scout_image.SetMask(true);
288
            scout_image.SetMaskColour(255, 255, 255);
289
        }
290
        else
291
        {
292
            scout_image.LoadFile(
293
                wxString::FromAscii((images_path + "scout.png").c_str()));
294
            scout_image.SetMask(true);
295
            scout_image.SetMaskColour(255, 255, 255);
296
        }
297

    
298
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
299
                   scout_image, Vector2(x, y), &path_bitmap, angle));
300
        scouts[real_name] = t;
301

    
302
        ghost_scouts.push_back(new GhostScout(ros::NodeHandle(real_name),
303
                scout_image, Vector2(x, y), &path_bitmap, angle, name));
304

    
305
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
306
                 real_name.c_str(), x, y, angle);
307

    
308
        return real_name;
309
    }
310

    
311
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
312
    {
313
        Close(true);
314
    }
315

    
316
    void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
317
    {
318
        wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
319
                       "\nThe Colony Project is a part of the Carnegie Mellon\n"
320
                       "Robotics Club. Our goal is to use cooperative low-cost\n"
321
                       "robots to solve challenging problems."),
322
                     _("About Scoutsim"),
323
                     wxOK | wxICON_INFORMATION, this );
324
    }
325

    
326
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
327
    {
328
        clear();
329
    }
330

    
331
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
332
    {
333
        display_map_name = map_base_name;
334
        clear();
335
    }
336

    
337
    void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
338
    {
339
        display_map_name = map_lines_name;
340
        clear();
341
    }
342
    
343
    void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
344
    {
345
        display_map_name = map_walls_name;
346
        clear();
347
    }
348

    
349
    void SimFrame::clear()
350
    {
351
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
352
        path_dc.Clear();
353

    
354
        sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0)));
355
        sonar_dc.Clear();
356

    
357
        sonar_dc.SelectObject(path_bitmap);
358

    
359
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
360
        path_dc.SelectObject(path_bitmap);
361
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
362
    }
363

    
364
    // Runs every REAL_TIME_REFRESH_RATE.
365
    void SimFrame::onUpdate(wxTimerEvent& evt)
366
    {
367
        ros::spinOnce();
368

    
369
        teleop();
370

    
371
        updateScouts();
372

    
373
        if (!ros::ok())
374
        {
375
            Close();
376
        }
377

    
378
        frame_count++;
379
    }
380

    
381
    void SimFrame::onPaint(wxPaintEvent& evt)
382
    {
383
        wxPaintDC dc(this);
384

    
385
        dc.DrawBitmap(path_bitmap, 0, 0, true);
386

    
387
        M_Scout::iterator it = scouts.begin();
388
        M_Scout::iterator end = scouts.end();
389
        for (; it != end; ++it)
390
        {
391
            it->second->paint(dc);
392
        }
393
        for (unsigned int i=0; i < ghost_scouts.size(); ++i)
394
        {
395
            ghost_scouts.at(i)->paint(dc);
396
        }
397
    }
398

    
399
    bool SimFrame::fileExists(const std::string& filename)
400
    {
401
        struct stat buf;
402
        if (stat(filename.c_str(), &buf) != -1)
403
        {
404
            return true;
405
        }
406
        return false;
407
    }
408

    
409
    void SimFrame::stopTeleop(wxCommandEvent& event)
410
    {
411
        teleop_type = TELEOP_OFF;
412
        teleop_l_speed = 0;
413
        teleop_r_speed = 0;
414
    }
415

    
416
    void SimFrame::startTeleopPrecise(wxCommandEvent& event)
417
    {
418
        teleop_type = TELEOP_PRECISE;
419
        teleop_l_speed = 0;
420
        teleop_r_speed = 0;
421
    }
422

    
423
    void SimFrame::startTeleopFluid(wxCommandEvent& event)
424
    {
425
        teleop_type = TELEOP_FLUID;
426
        teleop_l_speed = 0;
427
        teleop_r_speed = 0;
428
        teleop_fluid_speed = 0;
429
        teleop_fluid_omega = 0;
430
    }
431

    
432
    void SimFrame::teleop_move_precise()
433
    {
434
        // Default to stop
435
        teleop_l_speed = 0;
436
        teleop_r_speed = 0;
437

    
438
        if (wxGetKeyState(WXK_UP))
439
        {
440
            teleop_l_speed = TELEOP_PRECISE_SPEED;
441
            teleop_r_speed = TELEOP_PRECISE_SPEED;
442
        }
443
        else if (wxGetKeyState(WXK_DOWN))
444
        {
445
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
446
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
447
        }
448
        else if (wxGetKeyState(WXK_LEFT))
449
        {
450
            teleop_l_speed = -TELEOP_PRECISE_TURN_SPEED;
451
            teleop_r_speed = TELEOP_PRECISE_TURN_SPEED;
452
        }
453
        else if (wxGetKeyState(WXK_RIGHT))
454
        {
455
            teleop_l_speed = TELEOP_PRECISE_TURN_SPEED;
456
            teleop_r_speed = -TELEOP_PRECISE_TURN_SPEED;
457
        }
458
    }
459

    
460
    void SimFrame::teleop_move_fluid()
461
    {
462
        if (wxGetKeyState(WXK_UP))
463
        {
464
            teleop_fluid_speed += TELEOP_FLUID_INC * 2;
465
        }
466
        else if (wxGetKeyState(WXK_DOWN))
467
        {
468
            teleop_fluid_speed -= TELEOP_FLUID_INC * 2;
469
        }
470
        else if (teleop_fluid_speed > TELEOP_FLUID_INC)
471
        {
472
            teleop_fluid_speed -= TELEOP_FLUID_INC;
473
        }
474
        else if (teleop_fluid_speed < -TELEOP_FLUID_INC)
475
        {
476
            teleop_fluid_speed += TELEOP_FLUID_INC;
477
        }
478
        else
479
        {
480
            teleop_fluid_speed = 0;
481
        }
482

    
483
        if (wxGetKeyState(WXK_LEFT))
484
        {
485
            teleop_fluid_omega -= TELEOP_FLUID_INC * 2;
486
        }
487
        else if (wxGetKeyState(WXK_RIGHT))
488
        {
489
            teleop_fluid_omega += TELEOP_FLUID_INC * 2;
490
        }
491
        else
492
        {
493
            teleop_fluid_omega = 0;
494
        }
495

    
496
        if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
497
        {
498
            teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED;
499
        }
500
        else if (teleop_fluid_speed < -TELEOP_FLUID_MAX_SPEED)
501
        {
502
            teleop_fluid_speed = -TELEOP_FLUID_MAX_SPEED;
503
        }
504
        if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED)
505
        {
506
            teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED;
507
        }
508
        else if (teleop_fluid_omega < -TELEOP_FLUID_MAX_SPEED)
509
        {
510
            teleop_fluid_omega = -TELEOP_FLUID_MAX_SPEED;
511
        }
512

    
513
        int l_speed = teleop_fluid_speed + teleop_fluid_omega;
514
        int r_speed = teleop_fluid_speed - teleop_fluid_omega;
515

    
516
        teleop_l_speed = max(MIN_ABSOLUTE_SPEED,
517
                             min(MAX_ABSOLUTE_SPEED, l_speed));
518
        teleop_r_speed = max(MIN_ABSOLUTE_SPEED,
519
                             min(MAX_ABSOLUTE_SPEED, r_speed));
520
    }
521

    
522
    void SimFrame::teleop()
523
    {
524
        switch (teleop_type)
525
        {
526
            case TELEOP_OFF:
527
                return;
528
            case TELEOP_PRECISE:
529
                teleop_move_precise();
530
                break;
531
            case TELEOP_FLUID:
532
                teleop_move_fluid();
533
                break;
534
        }
535

    
536
        motors::set_motors msg;
537
        msg.fl_set = true;
538
        msg.fr_set = true;
539
        msg.bl_set = true;
540
        msg.br_set = true;
541
        msg.teleop_ON = true;
542

    
543
        msg.fl_speed = teleop_l_speed;
544
        msg.fr_speed = teleop_r_speed;
545
        msg.bl_speed = teleop_l_speed;
546
        msg.br_speed = teleop_r_speed;
547

    
548
        teleop_pub.publish(msg);
549
    }
550

    
551
    void SimFrame::updateScouts()
552
    {
553

    
554
        if (last_scout_update.isZero())
555
        {
556
            last_scout_update = ros::WallTime::now();
557
            return;
558
        }
559

    
560
        path_image = path_bitmap.ConvertToImage();
561
        Refresh();
562

    
563
        M_Scout::iterator it = scouts.begin();
564
        M_Scout::iterator end = scouts.end();
565

    
566
        world_state state;
567
        state.canvas_width = width_in_meters;
568
        state.canvas_height = height_in_meters;
569

    
570
        for (; it != end; ++it)
571
        {
572

    
573
            it->second->update(SIM_TIME_REFRESH_RATE,
574
                               path_dc, sonar_dc,
575
                               path_image, lines_image, walls_image,
576
                               path_dc.GetBackground().GetColour(),
577
                               sonar_dc.GetBackground().GetColour(),
578
                               state);
579
        }
580

    
581
        for (unsigned int i = 0; i < ghost_scouts.size(); ++i)
582
        {
583
            ghost_scouts.at(i)->update(SIM_TIME_REFRESH_RATE, path_dc, sonar_dc,
584
                path_dc.GetBackground().GetColour(), state);
585
        }
586

    
587
        frame_count++;
588
    }
589

    
590
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
591
                                 std_srvs::Empty::Response&)
592
    {
593
        ROS_INFO("Clearing scoutsim.");
594
        clear();
595
        return true;
596
    }
597

    
598
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
599
                                 std_srvs::Empty::Response&)
600
    {
601
        ROS_INFO("Resetting scoutsim.");
602
        scouts.clear();
603
        id_counter = 0;
604
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
605
        clear();
606
        return true;
607
    }
608

    
609
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
610
    {
611
        wireless_receive.publish(msg);
612
    }
613
}