Statistics
| Branch: | Revision:

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

History | View | Annotate | Download (11.6 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

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

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

    
121
        clear();
122

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

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

    
138
        ROS_INFO("Starting scoutsim with node name %s",
139
                 ros::this_node::getName().c_str()) ;
140

    
141
        wxMenu *menuFile = new wxMenu;
142
        menuFile->Append(ID_ABOUT, _("&About"));
143
        menuFile->AppendSeparator();
144
        menuFile->Append(ID_QUIT, _("E&xit"));
145

    
146
        wxMenu *menuSim = new wxMenu;
147
        menuSim->Append(ID_CLEAR, _("&Clear"));
148

    
149
        wxMenu *menuView = new wxMenu;
150
        menuView->Append(ID_MAP, _("&Map"));
151
        menuView->Append(ID_LINES, _("&Lines"));
152
        menuView->Append(ID_WALLS, _("&Walls"));
153

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

    
159
        SetMenuBar(menuBar);
160

    
161
        width_in_meters = GetSize().GetWidth() / meter;
162
        height_in_meters = GetSize().GetHeight() / meter;
163
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
164
    }
165

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

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

    
181
        res.name = name;
182

    
183
        return true;
184
    }
185

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

    
197
        scouts.erase(it);
198

    
199
        return true;
200
    }
201

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

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

    
228
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
229
                   scout_images[rand() % SCOUTSIM_NUM_SCOUTS],
230
                   Vector2(x, y), angle));
231
        scouts[real_name] = t;
232

    
233
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
234
                 real_name.c_str(), x, y, angle);
235

    
236
        return real_name;
237
    }
238

    
239
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
240
    {
241
        Close(true);
242
    }
243

    
244
    void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
245
    {
246
        wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
247
                       "\nThe Colony Project is a part of the Carnegie Mellon\n"
248
                       "Robotics Club. Our goal is to use cooperative low-cost\n"
249
                       "robots to solve challenging problems."),
250
                     _("About Scoutsim"),
251
                     wxOK | wxICON_INFORMATION, this );
252
    }
253

    
254
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
255
    {
256
        clear();
257
    }
258

    
259
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
260
    {
261
        display_map_name = map_base_name;
262
        clear();
263
    }
264

    
265
    void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
266
    {
267
        display_map_name = map_lines_name;
268
        clear();
269
    }
270
    
271
    void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
272
    {
273
        display_map_name = map_walls_name;
274
        clear();
275
    }
276

    
277
    void SimFrame::clear()
278
    {
279
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
280
        path_dc.Clear();
281

    
282
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
283
        path_dc.SelectObject(path_bitmap);
284
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
285
    }
286

    
287
    void SimFrame::onUpdate(wxTimerEvent& evt)
288
    {
289
        ros::spinOnce();
290

    
291
        updateScouts();
292

    
293
        if (!ros::ok())
294
        {
295
            Close();
296
        }
297
    }
298

    
299
    void SimFrame::onPaint(wxPaintEvent& evt)
300
    {
301
        wxPaintDC dc(this);
302

    
303
        dc.DrawBitmap(path_bitmap, 0, 0, true);
304

    
305
        M_Scout::iterator it = scouts.begin();
306
        M_Scout::iterator end = scouts.end();
307
        for (; it != end; ++it)
308
        {
309
            it->second->paint(dc);
310
        }
311
    }
312

    
313
    void SimFrame::updateScouts()
314
    {
315
        if (last_scout_update.isZero())
316
        {
317
            last_scout_update = ros::WallTime::now();
318
            return;
319
        }
320

    
321
        if (frame_count % 3 == 0)
322
        {
323
            path_image = path_bitmap.ConvertToImage();
324
            Refresh();
325
        }
326

    
327
        M_Scout::iterator it = scouts.begin();
328
        M_Scout::iterator end = scouts.end();
329

    
330
        world_state state;
331
        state.canvas_width = width_in_meters;
332
        state.canvas_height = height_in_meters;
333

    
334
        for (; it != end; ++it)
335
        {
336
            it->second->update(0.016, path_dc,
337
                               path_image, lines_image, walls_image,
338
                               path_dc.GetBackground().GetColour(),
339
                               state);
340
        }
341

    
342
        frame_count++;
343
    }
344

    
345
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
346
                                 std_srvs::Empty::Response&)
347
    {
348
        ROS_INFO("Clearing scoutsim.");
349
        clear();
350
        return true;
351
    }
352

    
353
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
354
                                 std_srvs::Empty::Response&)
355
    {
356
        ROS_INFO("Resetting scoutsim.");
357
        scouts.clear();
358
        id_counter = 0;
359
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
360
        clear();
361
        return true;
362
    }
363

    
364
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
365
    {
366
        wireless_receive.publish(msg);
367
    }
368
}