Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / sim_frame.cpp @ 0e0ef125

History | View | Annotate | Download (16.7 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(SCOUTSIM_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
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
91
        sonar_on = TRUE;
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

    
118
        // Subscribe and publisher wirless from robots
119
        wireless_receive = nh.advertise< ::messages::WirelessPacket>(
120
            "/wireless/receive", 1000); 
121
        wireless_send = nh.subscribe("/wireless/send", 1000,
122
            &SimFrame::wirelessCallback, this);
123

    
124
        // Teleop
125
        teleop_type = TELEOP_OFF;
126
        teleop_l_speed = 0;
127
        teleop_r_speed = 0;
128
        teleop_pub = nh.advertise<motors::set_motors>("/scout1/set_motors", 1000);
129

    
130
        ROS_INFO("Starting scoutsim with node name %s",
131
                 ros::this_node::getName().c_str()) ;
132

    
133
        wxMenu *menuFile = new wxMenu;
134
        menuFile->Append(ID_ABOUT, _("&About"));
135
        menuFile->AppendSeparator();
136
        menuFile->Append(ID_QUIT, _("E&xit"));
137

    
138
        wxMenu *menuSim = new wxMenu;
139
        menuSim->Append(ID_SONAR, _("S&onar"));
140
        menuSim->Append(ID_CLEAR, _("&Clear"));
141

    
142
        wxMenu *menuView = new wxMenu;
143
        menuView->Append(ID_MAP, _("&Map"));
144
        menuView->Append(ID_LINES, _("&Lines"));
145
        menuView->Append(ID_WALLS, _("&Walls"));
146

    
147
        wxMenu *menuTeleop = new wxMenu;
148
        menuTeleop->Append(ID_TELEOP_NONE, _("&None"));
149
        menuTeleop->Append(ID_TELEOP_PRECISE, _("&Precise"));
150
        menuTeleop->Append(ID_TELEOP_FLUID, _("&Fluid"));
151

    
152
        wxMenuBar *menuBar = new wxMenuBar;
153
        menuBar->Append(menuFile, _("&File"));
154
        menuBar->Append(menuSim, _("&Sim"));
155
        menuBar->Append(menuView, _("&View"));
156
        menuBar->Append(menuTeleop, _("&Teleop"));
157

    
158
        SetMenuBar(menuBar);
159

    
160
        width_in_meters = GetSize().GetWidth() / PIX_PER_METER;
161
        height_in_meters = GetSize().GetHeight() / PIX_PER_METER;
162
    }
163

    
164
    SimFrame::~SimFrame()
165
    {
166
        delete update_timer;
167
    }
168

    
169
    bool SimFrame::spawnCallback(scoutsim::Spawn::Request  &req,
170
                                 scoutsim::Spawn::Response &res)
171
    {
172
        std::string name = spawnScout(req.name, req.x, req.y, req.theta);
173
        if (name.empty())
174
        {
175
            ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
176
            return false;
177
        }
178

    
179
        res.name = name;
180

    
181
        return true;
182
    }
183

    
184
    bool SimFrame::killCallback(scoutsim::Kill::Request& req,
185
                                scoutsim::Kill::Response&)
186
    {
187
        M_Scout::iterator it = scouts.find(req.name);
188
        if (it == scouts.end())
189
        {
190
            ROS_ERROR("Tried to kill scout [%s], which does not exist",
191
                      req.name.c_str());
192
            return false;
193
        }
194

    
195
        scouts.erase(it);
196

    
197
        return true;
198
    }
199

    
200
    bool SimFrame::hasScout(const std::string& name)
201
    {
202
        return scouts.find(name) != scouts.end();
203
    }
204

    
205
    std::string SimFrame::spawnScout(const std::string& name,
206
                                     float x, float y, float angle)
207
    {
208
        std::string real_name = name;
209
        if (real_name.empty())
210
        {
211
            do
212
            {
213
                std::stringstream ss;
214
                ss << "scout" << ++id_counter;
215
                real_name = ss.str();
216
            } while (hasScout(real_name));
217
        }
218
        else
219
        {
220
            if (hasScout(real_name))
221
            {
222
                return "";
223
            }
224
        }
225

    
226
        wxImage scout_image;
227

    
228
        // Try to load a name-specific image; if not, load the default scout
229
        string specific_name = images_path + name + ".png";
230
        if (fileExists(specific_name))
231
        {
232
            scout_image.LoadFile(wxString::FromAscii(specific_name.c_str()));
233
            scout_image.SetMask(true);
234
            scout_image.SetMaskColour(255, 255, 255);
235
        }
236
        else
237
        {
238
            scout_image.LoadFile(
239
                wxString::FromAscii((images_path + "scout.png").c_str()));
240
            scout_image.SetMask(true);
241
            scout_image.SetMaskColour(255, 255, 255);
242
        }
243

    
244
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
245
                   scout_image, Vector2(x, y), &path_bitmap, angle));
246
        scouts[real_name] = t;
247

    
248
        ghost_scouts.push_back(new GhostScout(ros::NodeHandle(real_name),
249
                scout_image, Vector2(x, y), &path_bitmap, angle, name));
250

    
251
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
252
                 real_name.c_str(), x, y, angle);
253

    
254
        return real_name;
255
    }
256

    
257
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
258
    {
259
        Close(true);
260
    }
261

    
262
    void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
263
    {
264
        wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
265
                       "\nThe Colony Project is a part of the Carnegie Mellon\n"
266
                       "Robotics Club. Our goal is to use cooperative low-cost\n"
267
                       "robots to solve challenging problems."),
268
                     _("About Scoutsim"),
269
                     wxOK | wxICON_INFORMATION, this );
270
    }
271

    
272
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
273
    {
274
        clear();
275
    }
276

    
277
    void SimFrame::showSonar(wxCommandEvent& WXUNUSED(event))
278
    {
279
        sonar_on = not sonar_on;
280
        clear();
281
    }
282

    
283

    
284
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
285
    {
286
        display_map_name = map_base_name;
287
        clear();
288
    }
289

    
290
    void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
291
    {
292
        display_map_name = map_lines_name;
293
        clear();
294
    }
295
    
296
    void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
297
    {
298
        display_map_name = map_walls_name;
299
        clear();
300
    }
301

    
302
    void SimFrame::clear()
303
    {
304
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
305
        path_dc.Clear();
306

    
307
        sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0)));
308
        sonar_dc.Clear();
309

    
310
        sonar_dc.SelectObject(path_bitmap);
311

    
312
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
313
        path_dc.SelectObject(path_bitmap);
314
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
315
    }
316

    
317
    // Runs every SCOUTSIM_REFRESH_RATE.
318
    void SimFrame::onUpdate(wxTimerEvent& evt)
319
    {
320
        ros::spinOnce();
321

    
322
        teleop();
323

    
324
        updateScouts();
325

    
326
        if (!ros::ok())
327
        {
328
            Close();
329
        }
330
    }
331

    
332
    void SimFrame::onPaint(wxPaintEvent& evt)
333
    {
334
        wxPaintDC dc(this);
335

    
336
        dc.DrawBitmap(path_bitmap, 0, 0, true);
337

    
338
        M_Scout::iterator it = scouts.begin();
339
        M_Scout::iterator end = scouts.end();
340
        for (; it != end; ++it)
341
        {
342
            it->second->paint(dc);
343
        }
344
        for (unsigned int i=0; i<ghost_scouts.size(); ++i)
345
        {
346
            ghost_scouts.at(i)->paint(dc);
347
        }
348
    }
349

    
350
    bool SimFrame::fileExists(const std::string& filename)
351
    {
352
        struct stat buf;
353
        if (stat(filename.c_str(), &buf) != -1)
354
        {
355
            return true;
356
        }
357
        return false;
358
    }
359

    
360
    void SimFrame::stopTeleop(wxCommandEvent& event)
361
    {
362
        teleop_type = TELEOP_OFF;
363
        teleop_l_speed = 0;
364
        teleop_r_speed = 0;
365
    }
366

    
367
    void SimFrame::startTeleopPrecise(wxCommandEvent& event)
368
    {
369
        teleop_type = TELEOP_PRECISE;
370
        teleop_l_speed = 0;
371
        teleop_r_speed = 0;
372
    }
373

    
374
    void SimFrame::startTeleopFluid(wxCommandEvent& event)
375
    {
376
        teleop_type = TELEOP_FLUID;
377
        teleop_l_speed = 0;
378
        teleop_r_speed = 0;
379
        teleop_fluid_speed = 0;
380
        teleop_fluid_omega = 0;
381
    }
382

    
383
    void SimFrame::teleop_move_precise()
384
    {
385
        // Default to stop
386
        teleop_l_speed = 0;
387
        teleop_r_speed = 0;
388

    
389
        if (wxGetKeyState(WXK_UP))
390
        {
391
            teleop_l_speed = TELEOP_PRECISE_SPEED;
392
            teleop_r_speed = TELEOP_PRECISE_SPEED;
393
        }
394
        else if (wxGetKeyState(WXK_DOWN))
395
        {
396
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
397
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
398
        }
399
        else if (wxGetKeyState(WXK_LEFT))
400
        {
401
            teleop_l_speed = -TELEOP_PRECISE_SPEED * 2;
402
            teleop_r_speed = TELEOP_PRECISE_SPEED * 2;
403
        }
404
        else if (wxGetKeyState(WXK_RIGHT))
405
        {
406
            teleop_l_speed = TELEOP_PRECISE_SPEED * 2;
407
            teleop_r_speed = -TELEOP_PRECISE_SPEED * 2;
408
        }
409
    }
410

    
411
    void SimFrame::teleop_move_fluid()
412
    {
413
        if (wxGetKeyState(WXK_UP))
414
        {
415
            teleop_fluid_speed += TELEOP_FLUID_INC * 2;
416
        }
417
        else if (wxGetKeyState(WXK_DOWN))
418
        {
419
            teleop_fluid_speed -= TELEOP_FLUID_INC * 2;
420
        }
421
        else if (teleop_fluid_speed > 0)
422
        {
423
            teleop_fluid_speed -= TELEOP_FLUID_INC;
424
        }
425
        else if (teleop_fluid_speed < 0)
426
        {
427
            teleop_fluid_speed += TELEOP_FLUID_INC;
428
        }
429

    
430
        if (wxGetKeyState(WXK_LEFT))
431
        {
432
            teleop_fluid_omega -= TELEOP_FLUID_INC;
433
        }
434
        else if (wxGetKeyState(WXK_RIGHT))
435
        {
436
            teleop_fluid_omega += TELEOP_FLUID_INC;
437
        }
438
        else
439
        {
440
            teleop_fluid_omega = 0;
441
        }
442

    
443
        if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
444
        {
445
            teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED;
446
        }
447
        else if (teleop_fluid_speed < -TELEOP_FLUID_MAX_SPEED)
448
        {
449
            teleop_fluid_speed = -TELEOP_FLUID_MAX_SPEED;
450
        }
451
        if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED / 2)
452
        {
453
            teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED / 2;
454
        }
455
        else if (teleop_fluid_omega < -TELEOP_FLUID_MAX_SPEED / 2)
456
        {
457
            teleop_fluid_omega = -TELEOP_FLUID_MAX_SPEED / 2;
458
        }
459

    
460
        teleop_l_speed = teleop_fluid_speed + teleop_fluid_omega;
461
        teleop_r_speed = teleop_fluid_speed - teleop_fluid_omega;
462
    }
463

    
464
    void SimFrame::teleop()
465
    {
466
        switch (teleop_type)
467
        {
468
            case TELEOP_OFF:
469
                return;
470
            case TELEOP_PRECISE:
471
                teleop_move_precise();
472
                break;
473
            case TELEOP_FLUID:
474
                teleop_move_fluid();
475
                break;
476
        }
477

    
478
        motors::set_motors msg;
479
        msg.fl_set = true;
480
        msg.fr_set = true;
481
        msg.bl_set = true;
482
        msg.br_set = true;
483

    
484
        msg.fl_speed = teleop_l_speed;
485
        msg.fr_speed = teleop_r_speed;
486
        msg.bl_speed = teleop_l_speed;
487
        msg.br_speed = teleop_r_speed;
488

    
489
        teleop_pub.publish(msg);
490
    }
491

    
492
    void SimFrame::updateScouts()
493
    {
494
        if (last_scout_update.isZero())
495
        {
496
            last_scout_update = ros::WallTime::now();
497
            return;
498
        }
499

    
500
        if (frame_count % 3 == 0)
501
        {
502
            path_image = path_bitmap.ConvertToImage();
503
            Refresh();
504
        }
505

    
506
        M_Scout::iterator it = scouts.begin();
507
        M_Scout::iterator end = scouts.end();
508

    
509
        world_state state;
510
        state.canvas_width = width_in_meters;
511
        state.canvas_height = height_in_meters;
512

    
513
        for (; it != end; ++it)
514
        {
515
            it->second->update(0.016, path_dc,sonar_dc,sonar_on,
516
                               path_image, lines_image, walls_image,
517
                               path_dc.GetBackground().GetColour(),
518
                               sonar_dc.GetBackground().GetColour(),
519
                               state);
520
        }
521

    
522
        for (unsigned int i=0; i<ghost_scouts.size(); ++i)
523
        {
524
            ghost_scouts.at(i)->update(0.016, path_dc, sonar_dc,
525
                path_dc.GetBackground().GetColour(), state);
526
        }
527

    
528
        frame_count++;
529
    }
530

    
531
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
532
                                 std_srvs::Empty::Response&)
533
    {
534
        ROS_INFO("Clearing scoutsim.");
535
        clear();
536
        return true;
537
    }
538

    
539
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
540
                                 std_srvs::Empty::Response&)
541
    {
542
        ROS_INFO("Resetting scoutsim.");
543
        scouts.clear();
544
        id_counter = 0;
545
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
546
        clear();
547
        return true;
548
    }
549

    
550
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
551
    {
552
        wireless_receive.publish(msg);
553
    }
554
}