Project

General

Profile

Statistics
| Branch: | Revision:

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

History | View | Annotate | Download (16 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(16);
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
        // 200 pixels per meter. @todo make this a constant elsewhere.
81
        meter = 200;
82

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

    
91
        wxBitmap lines_bitmap;
92
        wxBitmap walls_bitmap;
93
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
94
        sonar_on = TRUE;
95

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

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

    
110
        clear();
111

    
112
        clear_srv = nh.advertiseService("clear",
113
                                        &SimFrame::clearCallback, this);
114
        reset_srv = nh.advertiseService("reset",
115
                                        &SimFrame::resetCallback, this);
116
        spawn_srv = nh.advertiseService("spawn",
117
                                        &SimFrame::spawnCallback, this);
118
        kill_srv = nh.advertiseService("kill",
119
                                       &SimFrame::killCallback, this);
120

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

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

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

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

    
141
        wxMenu *menuSim = new wxMenu;
142
        menuSim->Append(ID_SONAR, _("S&onar"));
143
        menuSim->Append(ID_CLEAR, _("&Clear"));
144

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

    
150
        wxMenu *menuTeleop = new wxMenu;
151
        menuTeleop->Append(ID_TELEOP_NONE, _("&None"));
152
        menuTeleop->Append(ID_TELEOP_PRECISE, _("&Precise"));
153
        menuTeleop->Append(ID_TELEOP_FLUID, _("&Fluid"));
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

    
161
        SetMenuBar(menuBar);
162

    
163
        width_in_meters = GetSize().GetWidth() / meter;
164
        height_in_meters = GetSize().GetHeight() / meter;
165
    }
166

    
167
    SimFrame::~SimFrame()
168
    {
169
        delete update_timer;
170
    }
171

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

    
182
        res.name = name;
183

    
184
        return true;
185
    }
186

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

    
198
        scouts.erase(it);
199

    
200
        return true;
201
    }
202

    
203
    bool SimFrame::hasScout(const std::string& name)
204
    {
205
        return scouts.find(name) != scouts.end();
206
    }
207

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

    
229
        wxImage scout_image;
230

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

    
247
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
248
                   scout_image, Vector2(x, y), &path_bitmap, angle));
249
        scouts[real_name] = t;
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
    void SimFrame::onUpdate(wxTimerEvent& evt)
318
    {
319
        ros::spinOnce();
320

    
321
        teleop();
322

    
323
        updateScouts();
324

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

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

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

    
337
        M_Scout::iterator it = scouts.begin();
338
        M_Scout::iterator end = scouts.end();
339
        for (; it != end; ++it)
340
        {
341
            it->second->paint(dc);
342
        }
343
    }
344

    
345
    bool SimFrame::fileExists(const std::string& filename)
346
    {
347
        struct stat buf;
348
        if (stat(filename.c_str(), &buf) != -1)
349
        {
350
            return true;
351
        }
352
        return false;
353
    }
354

    
355
    void SimFrame::stopTeleop(wxCommandEvent& event)
356
    {
357
        teleop_type = TELEOP_OFF;
358
        teleop_l_speed = 0;
359
        teleop_r_speed = 0;
360
    }
361

    
362
    void SimFrame::startTeleopPrecise(wxCommandEvent& event)
363
    {
364
        teleop_type = TELEOP_PRECISE;
365
        teleop_l_speed = 0;
366
        teleop_r_speed = 0;
367
    }
368

    
369
    void SimFrame::startTeleopFluid(wxCommandEvent& event)
370
    {
371
        teleop_type = TELEOP_FLUID;
372
        teleop_l_speed = 0;
373
        teleop_r_speed = 0;
374
        teleop_fluid_speed = 0;
375
        teleop_fluid_omega = 0;
376
    }
377

    
378
    void SimFrame::teleop_move_precise()
379
    {
380
        // Default to stop
381
        teleop_l_speed = 0;
382
        teleop_r_speed = 0;
383

    
384
        if (wxGetKeyState(WXK_UP))
385
        {
386
            teleop_l_speed = TELEOP_PRECISE_SPEED;
387
            teleop_r_speed = TELEOP_PRECISE_SPEED;
388
        }
389
        else if (wxGetKeyState(WXK_DOWN))
390
        {
391
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
392
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
393
        }
394
        else if (wxGetKeyState(WXK_LEFT))
395
        {
396
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
397
            teleop_r_speed = TELEOP_PRECISE_SPEED;
398
        }
399
        else if (wxGetKeyState(WXK_RIGHT))
400
        {
401
            teleop_l_speed = TELEOP_PRECISE_SPEED;
402
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
403
        }
404
    }
405

    
406
    void SimFrame::teleop_move_fluid()
407
    {
408
        if (wxGetKeyState(WXK_UP))
409
        {
410
            teleop_fluid_speed += 2;
411
        }
412
        else if (wxGetKeyState(WXK_DOWN))
413
        {
414
            teleop_fluid_speed -= 2;
415
        }
416
        else if (teleop_fluid_speed > 0)
417
        {
418
            teleop_fluid_speed -= 1;
419
        }
420
        else if (teleop_fluid_speed < 0)
421
        {
422
            teleop_fluid_speed += 1;
423
        }
424

    
425
        if (wxGetKeyState(WXK_LEFT))
426
        {
427
            teleop_fluid_omega -= 1;
428
        }
429
        else if (wxGetKeyState(WXK_RIGHT))
430
        {
431
            teleop_fluid_omega += 1;
432
        }
433
        else if (teleop_fluid_omega > 0)
434
        {
435
            teleop_fluid_omega -= 1;
436
        }
437
        else if (teleop_fluid_omega < 0)
438
        {
439
            teleop_fluid_omega += 1;
440
        }
441

    
442
        if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
443
        {
444
            teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED;
445
        }
446
        if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED / 2)
447
        {
448
            teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED / 2;
449
        }
450

    
451
        teleop_l_speed = teleop_fluid_speed + teleop_fluid_omega;
452
        teleop_r_speed = teleop_fluid_speed - teleop_fluid_omega;
453
    }
454

    
455
    void SimFrame::teleop()
456
    {
457
        switch (teleop_type)
458
        {
459
            case TELEOP_OFF:
460
                return;
461
            case TELEOP_PRECISE:
462
                teleop_move_precise();
463
                break;
464
            case TELEOP_FLUID:
465
                teleop_move_fluid();
466
                break;
467
        }
468

    
469
        motors::set_motors msg;
470
        msg.fl_set = true;
471
        msg.fr_set = true;
472
        msg.bl_set = true;
473
        msg.br_set = true;
474

    
475
        msg.fl_speed = teleop_l_speed;
476
        msg.fr_speed = teleop_r_speed;
477
        msg.bl_speed = teleop_l_speed;
478
        msg.br_speed = teleop_r_speed;
479

    
480
        teleop_pub.publish(msg);
481
    }
482

    
483
    void SimFrame::updateScouts()
484
    {
485
        if (last_scout_update.isZero())
486
        {
487
            last_scout_update = ros::WallTime::now();
488
            return;
489
        }
490

    
491
        if (frame_count % 3 == 0)
492
        {
493
            path_image = path_bitmap.ConvertToImage();
494
            Refresh();
495
        }
496

    
497
        M_Scout::iterator it = scouts.begin();
498
        M_Scout::iterator end = scouts.end();
499

    
500
        world_state state;
501
        state.canvas_width = width_in_meters;
502
        state.canvas_height = height_in_meters;
503

    
504
        for (; it != end; ++it)
505
        {
506
            it->second->update(0.016, path_dc,sonar_dc,sonar_on,
507
                               path_image, lines_image, walls_image,
508
                               path_dc.GetBackground().GetColour(),
509
                               sonar_dc.GetBackground().GetColour(),
510
                               state);
511
        }
512

    
513
        frame_count++;
514
    }
515

    
516
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
517
                                 std_srvs::Empty::Response&)
518
    {
519
        ROS_INFO("Clearing scoutsim.");
520
        clear();
521
        return true;
522
    }
523

    
524
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
525
                                 std_srvs::Empty::Response&)
526
    {
527
        ROS_INFO("Resetting scoutsim.");
528
        scouts.clear();
529
        id_counter = 0;
530
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
531
        clear();
532
        return true;
533
    }
534

    
535
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
536
    {
537
        wireless_receive.publish(msg);
538
    }
539
}