Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / sim_frame.cpp @ 68b23184

History | View | Annotate | Download (15.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(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
        std::string scouts[SCOUTSIM_NUM_SCOUTS] = 
79
        {
80
            "scout.png"
81
        };
82

    
83
        std::string images_path = ros::package::getPath("scoutsim")+"/images/";
84
        for (size_t i = 0; i < SCOUTSIM_NUM_SCOUTS; ++i)
85
        {
86
            scout_images[i].LoadFile(
87
                wxString::FromAscii((images_path + scouts[i]).c_str()));
88
            scout_images[i].SetMask(true);
89
            scout_images[i].SetMaskColour(255, 255, 255);
90
        }
91

    
92
        /// @todo This should change.
93
        meter = scout_images[0].GetHeight();
94

    
95
        map_base_name =  ros::package::getPath("scoutsim") + "/maps/" +
96
                           map_name + ".bmp";
97
        map_lines_name = ros::package::getPath("scoutsim") + "/maps/" +
98
                           map_name + "_lines.bmp";
99
        map_walls_name = ros::package::getPath("scoutsim") + "/maps/" +
100
                           map_name + "_walls.bmp";
101
        display_map_name = map_base_name;
102

    
103
        wxBitmap lines_bitmap;
104
        wxBitmap walls_bitmap;
105
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
106
        sonar_on = TRUE;
107

    
108
        // Try to load the file; if it fails, make a new blank file
109
        if (!lines_bitmap.LoadFile(wxString::FromAscii(map_lines_name.c_str())))
110
        {
111
            lines_bitmap = wxBitmap(path_bitmap.GetWidth(), path_bitmap.GetHeight(), 3);
112
        }
113
        lines_image = lines_bitmap.ConvertToImage();
114

    
115
        // Try to load the file; if it fails, make a new blank file
116
        if (!walls_bitmap.LoadFile(wxString::FromAscii(map_walls_name.c_str())))
117
        {
118
            walls_bitmap = wxBitmap(path_bitmap.GetWidth(), path_bitmap.GetHeight(), 3);
119
        }
120
        walls_image = walls_bitmap.ConvertToImage();
121

    
122
        clear();
123

    
124
        clear_srv = nh.advertiseService("clear",
125
                                        &SimFrame::clearCallback, this);
126
        reset_srv = nh.advertiseService("reset",
127
                                        &SimFrame::resetCallback, this);
128
        spawn_srv = nh.advertiseService("spawn",
129
                                        &SimFrame::spawnCallback, this);
130
        kill_srv = nh.advertiseService("kill",
131
                                       &SimFrame::killCallback, this);
132

    
133
        // Subscribe and publisher wirless from robots
134
        wireless_receive = nh.advertise< ::messages::WirelessPacket>(
135
            "/wireless/receive", 1000); 
136
        wireless_send = nh.subscribe("/wireless/send", 1000,
137
            &SimFrame::wirelessCallback, this);
138

    
139
        // Teleop
140
        teleop_type = TELEOP_OFF;
141
        teleop_l_speed = 0;
142
        teleop_r_speed = 0;
143
        teleop_pub = nh.advertise<motors::set_motors>("/scout1/set_motors", 1000);
144

    
145
        ROS_INFO("Starting scoutsim with node name %s",
146
                 ros::this_node::getName().c_str()) ;
147

    
148
        wxMenu *menuFile = new wxMenu;
149
        menuFile->Append(ID_ABOUT, _("&About"));
150
        menuFile->AppendSeparator();
151
        menuFile->Append(ID_QUIT, _("E&xit"));
152

    
153
        wxMenu *menuSim = new wxMenu;
154
        menuSim->Append(ID_SONAR, _("S&onar"));
155
        menuSim->Append(ID_CLEAR, _("&Clear"));
156

    
157
        wxMenu *menuView = new wxMenu;
158
        menuView->Append(ID_MAP, _("&Map"));
159
        menuView->Append(ID_LINES, _("&Lines"));
160
        menuView->Append(ID_WALLS, _("&Walls"));
161

    
162
        wxMenu *menuTeleop = new wxMenu;
163
        menuTeleop->Append(ID_TELEOP_NONE, _("&None"));
164
        menuTeleop->Append(ID_TELEOP_PRECISE, _("&Precise"));
165
        menuTeleop->Append(ID_TELEOP_FLUID, _("&Fluid"));
166

    
167
        wxMenuBar *menuBar = new wxMenuBar;
168
        menuBar->Append(menuFile, _("&File"));
169
        menuBar->Append(menuSim, _("&Sim"));
170
        menuBar->Append(menuView, _("&View"));
171
        menuBar->Append(menuTeleop, _("&Teleop"));
172

    
173
        SetMenuBar(menuBar);
174

    
175
        width_in_meters = GetSize().GetWidth() / meter;
176
        height_in_meters = GetSize().GetHeight() / meter;
177
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
178
    }
179

    
180
    SimFrame::~SimFrame()
181
    {
182
        delete update_timer;
183
    }
184

    
185
    bool SimFrame::spawnCallback(scoutsim::Spawn::Request  &req,
186
                                 scoutsim::Spawn::Response &res)
187
    {
188
        std::string name = spawnScout(req.name, req.x, req.y, req.theta);
189
        if (name.empty())
190
        {
191
            ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
192
            return false;
193
        }
194

    
195
        res.name = name;
196

    
197
        return true;
198
    }
199

    
200
    bool SimFrame::killCallback(scoutsim::Kill::Request& req,
201
                                scoutsim::Kill::Response&)
202
    {
203
        M_Scout::iterator it = scouts.find(req.name);
204
        if (it == scouts.end())
205
        {
206
            ROS_ERROR("Tried to kill scout [%s], which does not exist",
207
                      req.name.c_str());
208
            return false;
209
        }
210

    
211
        scouts.erase(it);
212

    
213
        return true;
214
    }
215

    
216
    bool SimFrame::hasScout(const std::string& name)
217
    {
218
        return scouts.find(name) != scouts.end();
219
    }
220

    
221
    std::string SimFrame::spawnScout(const std::string& name,
222
                                     float x, float y, float angle)
223
    {
224
        std::string real_name = name;
225
        if (real_name.empty())
226
        {
227
            do
228
            {
229
                std::stringstream ss;
230
                ss << "scout" << ++id_counter;
231
                real_name = ss.str();
232
            } while (hasScout(real_name));
233
        }
234
        else
235
        {
236
            if (hasScout(real_name))
237
            {
238
                return "";
239
            }
240
        }
241

    
242
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
243
                   scout_images[rand() % SCOUTSIM_NUM_SCOUTS],
244
                   Vector2(x, y), &path_bitmap,angle));
245
        scouts[real_name] = t;
246

    
247
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
248
                 real_name.c_str(), x, y, angle);
249

    
250
        return real_name;
251
    }
252

    
253
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
254
    {
255
        Close(true);
256
    }
257

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

    
268
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
269
    {
270
        clear();
271
    }
272

    
273
    void SimFrame::showSonar(wxCommandEvent& WXUNUSED(event))
274
    {
275
        sonar_on = not sonar_on;
276
        clear();
277
    }
278

    
279

    
280
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
281
    {
282
        display_map_name = map_base_name;
283
        clear();
284
    }
285

    
286
    void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
287
    {
288
        display_map_name = map_lines_name;
289
        clear();
290
    }
291
    
292
    void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
293
    {
294
        display_map_name = map_walls_name;
295
        clear();
296
    }
297

    
298
    void SimFrame::clear()
299
    {
300
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
301
        path_dc.Clear();
302

    
303
        sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0)));
304
        sonar_dc.Clear();
305

    
306
        sonar_dc.SelectObject(path_bitmap);
307

    
308
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
309
        path_dc.SelectObject(path_bitmap);
310
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
311
    }
312

    
313
    void SimFrame::onUpdate(wxTimerEvent& evt)
314
    {
315
        ros::spinOnce();
316

    
317
        teleop();
318

    
319
        updateScouts();
320

    
321
        if (!ros::ok())
322
        {
323
            Close();
324
        }
325
    }
326

    
327
    void SimFrame::onPaint(wxPaintEvent& evt)
328
    {
329
        wxPaintDC dc(this);
330

    
331
        dc.DrawBitmap(path_bitmap, 0, 0, true);
332

    
333
        M_Scout::iterator it = scouts.begin();
334
        M_Scout::iterator end = scouts.end();
335
        for (; it != end; ++it)
336
        {
337
            it->second->paint(dc);
338
        }
339
    }
340

    
341
    void SimFrame::stopTeleop(wxCommandEvent& event)
342
    {
343
        teleop_type = TELEOP_OFF;
344
        teleop_l_speed = 0;
345
        teleop_r_speed = 0;
346
    }
347

    
348
    void SimFrame::startTeleopPrecise(wxCommandEvent& event)
349
    {
350
        teleop_type = TELEOP_PRECISE;
351
        teleop_l_speed = 0;
352
        teleop_r_speed = 0;
353
    }
354

    
355
    void SimFrame::startTeleopFluid(wxCommandEvent& event)
356
    {
357
        teleop_type = TELEOP_FLUID;
358
        teleop_l_speed = 0;
359
        teleop_r_speed = 0;
360
        teleop_fluid_speed = 0;
361
        teleop_fluid_omega = 0;
362
    }
363

    
364
    void SimFrame::teleop_move_precise()
365
    {
366
        // Default to stop
367
        teleop_l_speed = 0;
368
        teleop_r_speed = 0;
369

    
370
        if (wxGetKeyState(WXK_UP))
371
        {
372
            teleop_l_speed = TELEOP_PRECISE_SPEED;
373
            teleop_r_speed = TELEOP_PRECISE_SPEED;
374
        }
375
        else if (wxGetKeyState(WXK_DOWN))
376
        {
377
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
378
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
379
        }
380
        else if (wxGetKeyState(WXK_LEFT))
381
        {
382
            teleop_l_speed = -TELEOP_PRECISE_SPEED;
383
            teleop_r_speed = TELEOP_PRECISE_SPEED;
384
        }
385
        else if (wxGetKeyState(WXK_RIGHT))
386
        {
387
            teleop_l_speed = TELEOP_PRECISE_SPEED;
388
            teleop_r_speed = -TELEOP_PRECISE_SPEED;
389
        }
390
    }
391

    
392
    void SimFrame::teleop_move_fluid()
393
    {
394
        if (wxGetKeyState(WXK_UP))
395
        {
396
            teleop_fluid_speed += 2;
397
        }
398
        else if (wxGetKeyState(WXK_DOWN))
399
        {
400
            teleop_fluid_speed -= 2;
401
        }
402
        else if (teleop_fluid_speed > 0)
403
        {
404
            teleop_fluid_speed -= 1;
405
        }
406
        else if (teleop_fluid_speed < 0)
407
        {
408
            teleop_fluid_speed += 1;
409
        }
410

    
411
        if (wxGetKeyState(WXK_LEFT))
412
        {
413
            teleop_fluid_omega -= 1;
414
        }
415
        else if (wxGetKeyState(WXK_RIGHT))
416
        {
417
            teleop_fluid_omega += 1;
418
        }
419
        else if (teleop_fluid_omega > 0)
420
        {
421
            teleop_fluid_omega -= 1;
422
        }
423
        else if (teleop_fluid_omega < 0)
424
        {
425
            teleop_fluid_omega += 1;
426
        }
427

    
428
        if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
429
        {
430
            teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED;
431
        }
432
        if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED / 2)
433
        {
434
            teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED / 2;
435
        }
436

    
437
        teleop_l_speed = teleop_fluid_speed + teleop_fluid_omega;
438
        teleop_r_speed = teleop_fluid_speed - teleop_fluid_omega;
439
    }
440

    
441
    void SimFrame::teleop()
442
    {
443
        switch (teleop_type)
444
        {
445
            case TELEOP_OFF:
446
                return;
447
            case TELEOP_PRECISE:
448
                teleop_move_precise();
449
                break;
450
            case TELEOP_FLUID:
451
                teleop_move_fluid();
452
                break;
453
        }
454

    
455
        motors::set_motors msg;
456
        msg.fl_set = true;
457
        msg.fr_set = true;
458
        msg.bl_set = true;
459
        msg.br_set = true;
460

    
461
        msg.fl_speed = teleop_l_speed;
462
        msg.fr_speed = teleop_r_speed;
463
        msg.bl_speed = teleop_l_speed;
464
        msg.br_speed = teleop_r_speed;
465

    
466
        teleop_pub.publish(msg);
467
    }
468

    
469
    void SimFrame::updateScouts()
470
    {
471
        if (last_scout_update.isZero())
472
        {
473
            last_scout_update = ros::WallTime::now();
474
            return;
475
        }
476

    
477
        if (frame_count % 3 == 0)
478
        {
479
            path_image = path_bitmap.ConvertToImage();
480
            Refresh();
481
        }
482

    
483
        M_Scout::iterator it = scouts.begin();
484
        M_Scout::iterator end = scouts.end();
485

    
486
        world_state state;
487
        state.canvas_width = width_in_meters;
488
        state.canvas_height = height_in_meters;
489

    
490
        for (; it != end; ++it)
491
        {
492
            it->second->update(0.016, path_dc,sonar_dc,sonar_on,
493
                               path_image, lines_image, walls_image,
494
                               path_dc.GetBackground().GetColour(),
495
                               sonar_dc.GetBackground().GetColour(),
496
                               state);
497
        }
498

    
499
        frame_count++;
500
    }
501

    
502
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
503
                                 std_srvs::Empty::Response&)
504
    {
505
        ROS_INFO("Clearing scoutsim.");
506
        clear();
507
        return true;
508
    }
509

    
510
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
511
                                 std_srvs::Empty::Response&)
512
    {
513
        ROS_INFO("Resetting scoutsim.");
514
        scouts.clear();
515
        id_counter = 0;
516
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
517
        clear();
518
        return true;
519
    }
520

    
521
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
522
    {
523
        wireless_receive.publish(msg);
524
    }
525
}