Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / scoutsim / src / sim_frame.cpp @ 9cb9623b

History | View | Annotate | Download (17.3 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_visual_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_PRECISE;
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
        wxMenu *menuTest = new wxMenu;
153
        menuTest->Append(ID_TEST, _("&Scouts go here"));
154

    
155
        wxMenuBar *menuBar = new wxMenuBar;
156
        menuBar->Append(menuFile, _("&File"));
157
        menuBar->Append(menuSim, _("&Sim"));
158
        menuBar->Append(menuView, _("&View"));
159
        menuBar->Append(menuTeleop, _("&Teleop"));
160
        menuBar->Append(menuTest, _("T&est"));
161

    
162
        SetMenuBar(menuBar);
163

    
164
        width_in_meters = GetSize().GetWidth() / PIX_PER_METER;
165
        height_in_meters = GetSize().GetHeight() / PIX_PER_METER;
166

    
167
        spawnScout("scout1", 1.4, .78, 0);
168
    }
169

    
170
    SimFrame::~SimFrame()
171
    {
172
        delete update_timer;
173
    }
174

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

    
185
        res.name = name;
186

    
187
        return true;
188
    }
189

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

    
201
        scouts.erase(it);
202

    
203
        return true;
204
    }
205

    
206
    bool SimFrame::hasScout(const std::string& name)
207
    {
208
        return scouts.find(name) != scouts.end();
209
    }
210

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

    
232
        wxImage scout_image;
233

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

    
250
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
251
                   scout_image, Vector2(x, y), &path_bitmap, angle));
252
        scouts[real_name] = t;
253

    
254
        ghost_scouts.push_back(new GhostScout(ros::NodeHandle(real_name),
255
                scout_image, Vector2(x, y), &path_bitmap, angle, name));
256

    
257
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
258
                 real_name.c_str(), x, y, angle);
259

    
260
        return real_name;
261
    }
262

    
263
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
264
    {
265
        Close(true);
266
    }
267

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

    
278
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
279
    {
280
        clear();
281
    }
282

    
283
    void SimFrame::showSonar(wxCommandEvent& WXUNUSED(event))
284
    {
285
        sonar_visual_on = not sonar_visual_on;
286
        clear();
287
    }
288

    
289
    void SimFrame::doTest(wxCommandEvent& WXUNUSED(event))
290
    {
291
        clear();
292
    }
293

    
294
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
295
    {
296
        display_map_name = map_base_name;
297
        clear();
298
    }
299

    
300
    void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
301
    {
302
        display_map_name = map_lines_name;
303
        clear();
304
    }
305
    
306
    void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
307
    {
308
        display_map_name = map_walls_name;
309
        clear();
310
    }
311

    
312
    void SimFrame::clear()
313
    {
314
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
315
        path_dc.Clear();
316

    
317
        sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0)));
318
        sonar_dc.Clear();
319

    
320
        sonar_dc.SelectObject(path_bitmap);
321

    
322
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
323
        path_dc.SelectObject(path_bitmap);
324
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
325
    }
326

    
327
    // Runs every SCOUTSIM_REFRESH_RATE.
328
    void SimFrame::onUpdate(wxTimerEvent& evt)
329
    {
330
        ros::spinOnce();
331

    
332
        teleop();
333

    
334
        updateScouts();
335

    
336
        if (!ros::ok())
337
        {
338
            Close();
339
        }
340

    
341
        frame_count++;
342
    }
343

    
344
    void SimFrame::onPaint(wxPaintEvent& evt)
345
    {
346
        wxPaintDC dc(this);
347

    
348
        dc.DrawBitmap(path_bitmap, 0, 0, true);
349

    
350
        M_Scout::iterator it = scouts.begin();
351
        M_Scout::iterator end = scouts.end();
352
        for (; it != end; ++it)
353
        {
354
            it->second->paint(dc);
355
        }
356
        for (unsigned int i=0; i<ghost_scouts.size(); ++i)
357
        {
358
            ghost_scouts.at(i)->paint(dc);
359
        }
360
    }
361

    
362
    bool SimFrame::fileExists(const std::string& filename)
363
    {
364
        struct stat buf;
365
        if (stat(filename.c_str(), &buf) != -1)
366
        {
367
            return true;
368
        }
369
        return false;
370
    }
371

    
372
    void SimFrame::stopTeleop(wxCommandEvent& event)
373
    {
374
        teleop_type = TELEOP_OFF;
375
        teleop_l_speed = 0;
376
        teleop_r_speed = 0;
377
    }
378

    
379
    void SimFrame::startTeleopPrecise(wxCommandEvent& event)
380
    {
381
        teleop_type = TELEOP_PRECISE;
382
        teleop_l_speed = 0;
383
        teleop_r_speed = 0;
384
    }
385

    
386
    void SimFrame::startTeleopFluid(wxCommandEvent& event)
387
    {
388
        teleop_type = TELEOP_FLUID;
389
        teleop_l_speed = 0;
390
        teleop_r_speed = 0;
391
        teleop_fluid_speed = 0;
392
        teleop_fluid_omega = 0;
393
    }
394

    
395
    void SimFrame::teleop_move_precise()
396
    {
397
        // Default to stop
398
        teleop_l_speed = 0;
399
        teleop_r_speed = 0;
400

    
401
        if (wxGetKeyState(WXK_UP))
402
        {
403
            teleop_l_speed = TELEOP_PRECISE_SPEED;
404
            teleop_r_speed = TELEOP_PRECISE_SPEED;
405
        }
406
        else if (wxGetKeyState(WXK_DOWN))
407
        {
408
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
409
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
410
        }
411
        else if (wxGetKeyState(WXK_LEFT))
412
        {
413
            teleop_l_speed = -TELEOP_PRECISE_SPEED * 2;
414
            teleop_r_speed = TELEOP_PRECISE_SPEED * 2;
415
        }
416
        else if (wxGetKeyState(WXK_RIGHT))
417
        {
418
            teleop_l_speed = TELEOP_PRECISE_SPEED * 2;
419
            teleop_r_speed = -TELEOP_PRECISE_SPEED * 2;
420
        }
421
    }
422

    
423
    void SimFrame::teleop_move_fluid()
424
    {
425
        if (wxGetKeyState(WXK_UP))
426
        {
427
            teleop_fluid_speed += TELEOP_FLUID_INC * 2;
428
        }
429
        else if (wxGetKeyState(WXK_DOWN))
430
        {
431
            teleop_fluid_speed -= TELEOP_FLUID_INC * 2;
432
        }
433
        else if (teleop_fluid_speed > TELEOP_FLUID_INC)
434
        {
435
            teleop_fluid_speed -= TELEOP_FLUID_INC;
436
        }
437
        else if (teleop_fluid_speed < -TELEOP_FLUID_INC)
438
        {
439
            teleop_fluid_speed += TELEOP_FLUID_INC;
440
        }
441
        else
442
        {
443
            teleop_fluid_speed = 0;
444
        }
445

    
446
        if (wxGetKeyState(WXK_LEFT))
447
        {
448
            teleop_fluid_omega -= TELEOP_FLUID_INC;
449
        }
450
        else if (wxGetKeyState(WXK_RIGHT))
451
        {
452
            teleop_fluid_omega += TELEOP_FLUID_INC;
453
        }
454
        else
455
        {
456
            teleop_fluid_omega = 0;
457
        }
458

    
459
        if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
460
        {
461
            teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED;
462
        }
463
        else if (teleop_fluid_speed < -TELEOP_FLUID_MAX_SPEED)
464
        {
465
            teleop_fluid_speed = -TELEOP_FLUID_MAX_SPEED;
466
        }
467
        if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED)
468
        {
469
            teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED;
470
        }
471
        else if (teleop_fluid_omega < -TELEOP_FLUID_MAX_SPEED)
472
        {
473
            teleop_fluid_omega = -TELEOP_FLUID_MAX_SPEED;
474
        }
475

    
476
        int l_speed = teleop_fluid_speed + teleop_fluid_omega;
477
        int r_speed = teleop_fluid_speed - teleop_fluid_omega;
478

    
479
        teleop_l_speed = max(MIN_ABSOLUTE_SPEED,
480
                             min(MAX_ABSOLUTE_SPEED, l_speed));
481
        teleop_r_speed = max(MIN_ABSOLUTE_SPEED,
482
                             min(MAX_ABSOLUTE_SPEED, r_speed));
483
    }
484

    
485
    void SimFrame::teleop()
486
    {
487
        switch (teleop_type)
488
        {
489
            case TELEOP_OFF:
490
                return;
491
            case TELEOP_PRECISE:
492
                teleop_move_precise();
493
                break;
494
            case TELEOP_FLUID:
495
                teleop_move_fluid();
496
                break;
497
        }
498

    
499
        motors::set_motors msg;
500
        msg.fl_set = true;
501
        msg.fr_set = true;
502
        msg.bl_set = true;
503
        msg.br_set = true;
504

    
505
        msg.fl_speed = teleop_l_speed;
506
        msg.fr_speed = teleop_r_speed;
507
        msg.bl_speed = teleop_l_speed;
508
        msg.br_speed = teleop_r_speed;
509

    
510
        teleop_pub.publish(msg);
511
    }
512

    
513
    void SimFrame::updateScouts()
514
    {
515
        if (last_scout_update.isZero())
516
        {
517
            last_scout_update = ros::WallTime::now();
518
            return;
519
        }
520

    
521
        path_image = path_bitmap.ConvertToImage();
522
        Refresh();
523

    
524
        M_Scout::iterator it = scouts.begin();
525
        M_Scout::iterator end = scouts.end();
526

    
527
        world_state state;
528
        state.canvas_width = width_in_meters;
529
        state.canvas_height = height_in_meters;
530

    
531
        for (; it != end; ++it)
532
        {
533
            it->second->update(SCOUTSIM_REFRESH_RATE,
534
                               path_dc,sonar_dc, sonar_visual_on,
535
                               path_image, lines_image, walls_image,
536
                               path_dc.GetBackground().GetColour(),
537
                               sonar_dc.GetBackground().GetColour(),
538
                               state);
539
        }
540

    
541
        for (unsigned int i=0; i<ghost_scouts.size(); ++i)
542
        {
543
            ghost_scouts.at(i)->update(0.016, path_dc, sonar_dc,
544
                path_dc.GetBackground().GetColour(), state);
545
        }
546

    
547
        frame_count++;
548
    }
549

    
550
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
551
                                 std_srvs::Empty::Response&)
552
    {
553
        ROS_INFO("Clearing scoutsim.");
554
        clear();
555
        return true;
556
    }
557

    
558
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
559
                                 std_srvs::Empty::Response&)
560
    {
561
        ROS_INFO("Resetting scoutsim.");
562
        scouts.clear();
563
        id_counter = 0;
564
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
565
        clear();
566
        return true;
567
    }
568

    
569
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
570
    {
571
        wireless_receive.publish(msg);
572
    }
573
}