Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / sim_frame.cpp @ dd065971

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

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

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

    
106
        clear();
107

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

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

    
129
        // Teleop
130
        teleop_type = TELEOP_OFF;
131
        teleop_l_speed = 0;
132
        teleop_r_speed = 0;
133
        teleop_pub = nh.advertise<motors::set_motors>("/scout1/set_motors", 1000);
134

    
135
        ROS_INFO("Starting scoutsim with node name %s",
136
                 ros::this_node::getName().c_str()) ;
137

    
138
        wxMenu *menuFile = new wxMenu;
139
        menuFile->Append(ID_ABOUT, _("&About"));
140
        menuFile->AppendSeparator();
141
        menuFile->Append(ID_QUIT, _("E&xit"));
142

    
143
        wxMenu *menuSim = new wxMenu;
144
        menuSim->Append(ID_CLEAR, _("&Clear"));
145

    
146
        wxMenu *menuView = new wxMenu;
147
        menuView->Append(ID_MAP, _("&Map"));
148
        menuView->Append(ID_LINES, _("&Lines"));
149
        menuView->Append(ID_WALLS, _("&Walls"));
150

    
151
        wxMenu *menuTeleop = new wxMenu;
152
        menuTeleop->Append(ID_TELEOP_NONE, _("&None"));
153
        menuTeleop->Append(ID_TELEOP_PRECISE, _("&Precise"));
154
        menuTeleop->Append(ID_TELEOP_FLUID, _("&Fluid"));
155

    
156
        wxMenuBar *menuBar = new wxMenuBar;
157
        menuBar->Append(menuFile, _("&File"));
158
        menuBar->Append(menuSim, _("&Sim"));
159
        menuBar->Append(menuView, _("&View"));
160
        menuBar->Append(menuTeleop, _("&Teleop"));
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_WARN("A scout named [%s] already exists", req.name.c_str());
182
            return false;
183
        }
184

    
185
        res.name = name;
186
        return true;
187
    }
188

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

    
200
        scouts.erase(it);
201

    
202
        return true;
203
    }
204

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

    
216
        it->second->set_sonar_visual(req.on);
217
        return true;
218
    }
219

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

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

    
237
    bool SimFrame::setTeleopCallback(SetTeleop::Request& req,
238
                                     SetTeleop::Response&)
239
    {
240
        std::stringstream ss;
241
        ss << "/" << req.scout_name << "/set_motors";
242
        teleop_pub = nh.advertise<motors::set_motors>(ss.str(), 1000);
243

    
244
        return true;
245
    }
246

    
247
    bool SimFrame::hasScout(const std::string& name)
248
    {
249
        return scouts.find(name) != scouts.end();
250
    }
251

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

    
275
        wxImage scout_image;
276

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

    
293
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
294
                   scout_image, Vector2(x, y), &path_bitmap, angle));
295
        scouts[real_name] = t;
296

    
297
        ghost_scouts.push_back(new GhostScout(ros::NodeHandle(real_name),
298
                scout_image, Vector2(x, y), &path_bitmap, angle, name));
299

    
300
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
301
                 real_name.c_str(), x, y, angle);
302

    
303
        return real_name;
304
    }
305

    
306
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
307
    {
308
        Close(true);
309
    }
310

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

    
321
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
322
    {
323
        clear();
324
    }
325

    
326
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
327
    {
328
        display_map_name = map_base_name;
329
        clear();
330
    }
331

    
332
    void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
333
    {
334
        display_map_name = map_lines_name;
335
        clear();
336
    }
337
    
338
    void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
339
    {
340
        display_map_name = map_walls_name;
341
        clear();
342
    }
343

    
344
    void SimFrame::clear()
345
    {
346
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
347
        path_dc.Clear();
348

    
349
        sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0)));
350
        sonar_dc.Clear();
351

    
352
        sonar_dc.SelectObject(path_bitmap);
353

    
354
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
355
        path_dc.SelectObject(path_bitmap);
356
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
357
    }
358

    
359
    // Runs every REAL_TIME_REFRESH_RATE.
360
    void SimFrame::onUpdate(wxTimerEvent& evt)
361
    {
362
        ros::spinOnce();
363

    
364
        teleop();
365

    
366
        updateScouts();
367

    
368
        if (!ros::ok())
369
        {
370
            Close();
371
        }
372

    
373
        frame_count++;
374
    }
375

    
376
    void SimFrame::onPaint(wxPaintEvent& evt)
377
    {
378
        wxPaintDC dc(this);
379

    
380
        dc.DrawBitmap(path_bitmap, 0, 0, true);
381

    
382
        M_Scout::iterator it = scouts.begin();
383
        M_Scout::iterator end = scouts.end();
384
        for (; it != end; ++it)
385
        {
386
            it->second->paint(dc);
387
        }
388
        for (unsigned int i=0; i < ghost_scouts.size(); ++i)
389
        {
390
            ghost_scouts.at(i)->paint(dc);
391
        }
392
    }
393

    
394
    bool SimFrame::fileExists(const std::string& filename)
395
    {
396
        struct stat buf;
397
        if (stat(filename.c_str(), &buf) != -1)
398
        {
399
            return true;
400
        }
401
        return false;
402
    }
403

    
404
    void SimFrame::stopTeleop(wxCommandEvent& event)
405
    {
406
        teleop_type = TELEOP_OFF;
407
        teleop_l_speed = 0;
408
        teleop_r_speed = 0;
409
    }
410

    
411
    void SimFrame::startTeleopPrecise(wxCommandEvent& event)
412
    {
413
        teleop_type = TELEOP_PRECISE;
414
        teleop_l_speed = 0;
415
        teleop_r_speed = 0;
416
    }
417

    
418
    void SimFrame::startTeleopFluid(wxCommandEvent& event)
419
    {
420
        teleop_type = TELEOP_FLUID;
421
        teleop_l_speed = 0;
422
        teleop_r_speed = 0;
423
        teleop_fluid_speed = 0;
424
        teleop_fluid_omega = 0;
425
    }
426

    
427
    void SimFrame::teleop_move_precise()
428
    {
429
        // Default to stop
430
        teleop_l_speed = 0;
431
        teleop_r_speed = 0;
432

    
433
        if (wxGetKeyState(WXK_UP))
434
        {
435
            teleop_l_speed = TELEOP_PRECISE_SPEED;
436
            teleop_r_speed = TELEOP_PRECISE_SPEED;
437
        }
438
        else if (wxGetKeyState(WXK_DOWN))
439
        {
440
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
441
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
442
        }
443
        else if (wxGetKeyState(WXK_LEFT))
444
        {
445
            teleop_l_speed = -TELEOP_PRECISE_TURN_SPEED;
446
            teleop_r_speed = TELEOP_PRECISE_TURN_SPEED;
447
        }
448
        else if (wxGetKeyState(WXK_RIGHT))
449
        {
450
            teleop_l_speed = TELEOP_PRECISE_TURN_SPEED;
451
            teleop_r_speed = -TELEOP_PRECISE_TURN_SPEED;
452
        }
453
    }
454

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

    
478
        if (wxGetKeyState(WXK_LEFT))
479
        {
480
            teleop_fluid_omega -= TELEOP_FLUID_INC * 2;
481
        }
482
        else if (wxGetKeyState(WXK_RIGHT))
483
        {
484
            teleop_fluid_omega += TELEOP_FLUID_INC * 2;
485
        }
486
        else
487
        {
488
            teleop_fluid_omega = 0;
489
        }
490

    
491
        if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
492
        {
493
            teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED;
494
        }
495
        else if (teleop_fluid_speed < -TELEOP_FLUID_MAX_SPEED)
496
        {
497
            teleop_fluid_speed = -TELEOP_FLUID_MAX_SPEED;
498
        }
499
        if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED)
500
        {
501
            teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED;
502
        }
503
        else if (teleop_fluid_omega < -TELEOP_FLUID_MAX_SPEED)
504
        {
505
            teleop_fluid_omega = -TELEOP_FLUID_MAX_SPEED;
506
        }
507

    
508
        int l_speed = teleop_fluid_speed + teleop_fluid_omega;
509
        int r_speed = teleop_fluid_speed - teleop_fluid_omega;
510

    
511
        teleop_l_speed = max(MIN_ABSOLUTE_SPEED,
512
                             min(MAX_ABSOLUTE_SPEED, l_speed));
513
        teleop_r_speed = max(MIN_ABSOLUTE_SPEED,
514
                             min(MAX_ABSOLUTE_SPEED, r_speed));
515
    }
516

    
517
    void SimFrame::teleop()
518
    {
519
        switch (teleop_type)
520
        {
521
            case TELEOP_OFF:
522
                return;
523
            case TELEOP_PRECISE:
524
                teleop_move_precise();
525
                break;
526
            case TELEOP_FLUID:
527
                teleop_move_fluid();
528
                break;
529
        }
530

    
531
        motors::set_motors msg;
532
        msg.fl_set = true;
533
        msg.fr_set = true;
534
        msg.bl_set = true;
535
        msg.br_set = true;
536

    
537
        msg.fl_speed = teleop_l_speed;
538
        msg.fr_speed = teleop_r_speed;
539
        msg.bl_speed = teleop_l_speed;
540
        msg.br_speed = teleop_r_speed;
541

    
542
        teleop_pub.publish(msg);
543
    }
544

    
545
    void SimFrame::updateScouts()
546
    {
547
        if (last_scout_update.isZero())
548
        {
549
            last_scout_update = ros::WallTime::now();
550
            return;
551
        }
552

    
553
        path_image = path_bitmap.ConvertToImage();
554
        Refresh();
555

    
556
        M_Scout::iterator it = scouts.begin();
557
        M_Scout::iterator end = scouts.end();
558

    
559
        world_state state;
560
        state.canvas_width = width_in_meters;
561
        state.canvas_height = height_in_meters;
562

    
563
        for (; it != end; ++it)
564
        {
565
            it->second->update(SIM_TIME_REFRESH_RATE,
566
                               path_dc, sonar_dc,
567
                               path_image, lines_image, walls_image,
568
                               path_dc.GetBackground().GetColour(),
569
                               sonar_dc.GetBackground().GetColour(),
570
                               state);
571
        }
572

    
573
        for (unsigned int i = 0; i < ghost_scouts.size(); ++i)
574
        {
575
            ghost_scouts.at(i)->update(SIM_TIME_REFRESH_RATE, path_dc, sonar_dc,
576
                path_dc.GetBackground().GetColour(), state);
577
        }
578

    
579
        frame_count++;
580
    }
581

    
582
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
583
                                 std_srvs::Empty::Response&)
584
    {
585
        ROS_INFO("Clearing scoutsim.");
586
        clear();
587
        return true;
588
    }
589

    
590
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
591
                                 std_srvs::Empty::Response&)
592
    {
593
        ROS_INFO("Resetting scoutsim.");
594
        scouts.clear();
595
        id_counter = 0;
596
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
597
        clear();
598
        return true;
599
    }
600

    
601
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
602
    {
603
        wireless_receive.publish(msg);
604
    }
605
}