Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / sim_frame.cpp @ 71e1154d

History | View | Annotate | Download (11.2 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
        lines_bitmap.LoadFile(wxString::FromAscii(map_lines_name.c_str()));
105
        lines_image = lines_bitmap.ConvertToImage();
106

    
107
        wxBitmap walls_bitmap;
108
        walls_bitmap.LoadFile(wxString::FromAscii(map_walls_name.c_str()));
109
        walls_image = walls_bitmap.ConvertToImage();
110

    
111
        clear();
112

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

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

    
128
        ROS_INFO("Starting scoutsim with node name %s",
129
                 ros::this_node::getName().c_str()) ;
130

    
131
        wxMenu *menuFile = new wxMenu;
132
        menuFile->Append(ID_ABOUT, _("&About"));
133
        menuFile->AppendSeparator();
134
        menuFile->Append(ID_QUIT, _("E&xit"));
135

    
136
        wxMenu *menuSim = new wxMenu;
137
        menuSim->Append(ID_CLEAR, _("&Clear"));
138

    
139
        wxMenu *menuView = new wxMenu;
140
        menuView->Append(ID_MAP, _("&Map"));
141
        menuView->Append(ID_LINES, _("&Lines"));
142
        menuView->Append(ID_WALLS, _("&Walls"));
143

    
144
        wxMenuBar *menuBar = new wxMenuBar;
145
        menuBar->Append(menuFile, _("&File"));
146
        menuBar->Append(menuSim, _("&Sim"));
147
        menuBar->Append(menuView, _("&View"));
148

    
149
        SetMenuBar(menuBar);
150

    
151
        width_in_meters = GetSize().GetWidth() / meter;
152
        height_in_meters = GetSize().GetHeight() / meter;
153
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
154
    }
155

    
156
    SimFrame::~SimFrame()
157
    {
158
        delete update_timer;
159
    }
160

    
161
    bool SimFrame::spawnCallback(scoutsim::Spawn::Request  &req,
162
                                 scoutsim::Spawn::Response &res)
163
    {
164
        std::string name = spawnScout(req.name, req.x, req.y, req.theta);
165
        if (name.empty())
166
        {
167
            ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
168
            return false;
169
        }
170

    
171
        res.name = name;
172

    
173
        return true;
174
    }
175

    
176
    bool SimFrame::killCallback(scoutsim::Kill::Request& req,
177
                                scoutsim::Kill::Response&)
178
    {
179
        M_Scout::iterator it = scouts.find(req.name);
180
        if (it == scouts.end())
181
        {
182
            ROS_ERROR("Tried to kill scout [%s], which does not exist",
183
                      req.name.c_str());
184
            return false;
185
        }
186

    
187
        scouts.erase(it);
188

    
189
        return true;
190
    }
191

    
192
    bool SimFrame::hasScout(const std::string& name)
193
    {
194
        return scouts.find(name) != scouts.end();
195
    }
196

    
197
    std::string SimFrame::spawnScout(const std::string& name,
198
                                     float x, float y, float angle)
199
    {
200
        std::string real_name = name;
201
        if (real_name.empty())
202
        {
203
            do
204
            {
205
                std::stringstream ss;
206
                ss << "scout" << ++id_counter;
207
                real_name = ss.str();
208
            } while (hasScout(real_name));
209
        }
210
        else
211
        {
212
            if (hasScout(real_name))
213
            {
214
                return "";
215
            }
216
        }
217

    
218
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
219
                   scout_images[rand() % SCOUTSIM_NUM_SCOUTS],
220
                   Vector2(x, y), angle));
221
        scouts[real_name] = t;
222

    
223
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
224
                 real_name.c_str(), x, y, angle);
225

    
226
        return real_name;
227
    }
228

    
229
    void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
230
    {
231
        Close(true);
232
    }
233

    
234
    void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
235
    {
236
        wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
237
                       "\nThe Colony Project is a part of the Carnegie Mellon\n"
238
                       "Robotics Club. Our goal is to use cooperative low-cost\n"
239
                       "robots to solve challenging problems."),
240
                     _("About Scoutsim"),
241
                     wxOK | wxICON_INFORMATION, this );
242
    }
243

    
244
    void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
245
    {
246
        clear();
247
    }
248

    
249
    void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
250
    {
251
        display_map_name = map_base_name;
252
        clear();
253
    }
254

    
255
    void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
256
    {
257
        display_map_name = map_lines_name;
258
        clear();
259
    }
260
    
261
    void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
262
    {
263
        display_map_name = map_walls_name;
264
        clear();
265
    }
266

    
267
    void SimFrame::clear()
268
    {
269
        path_dc.SetBackground(wxBrush(wxColour(100, 100, 100)));
270
        path_dc.Clear();
271

    
272
        path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str()));
273
        path_dc.SelectObject(path_bitmap);
274
        SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight()));
275
    }
276

    
277
    void SimFrame::onUpdate(wxTimerEvent& evt)
278
    {
279
        ros::spinOnce();
280

    
281
        updateScouts();
282

    
283
        if (!ros::ok())
284
        {
285
            Close();
286
        }
287
    }
288

    
289
    void SimFrame::onPaint(wxPaintEvent& evt)
290
    {
291
        wxPaintDC dc(this);
292

    
293
        dc.DrawBitmap(path_bitmap, 0, 0, true);
294

    
295
        M_Scout::iterator it = scouts.begin();
296
        M_Scout::iterator end = scouts.end();
297
        for (; it != end; ++it)
298
        {
299
            it->second->paint(dc);
300
        }
301
    }
302

    
303
    void SimFrame::updateScouts()
304
    {
305
        if (last_scout_update.isZero())
306
        {
307
            last_scout_update = ros::WallTime::now();
308
            return;
309
        }
310

    
311
        if (frame_count % 3 == 0)
312
        {
313
            path_image = path_bitmap.ConvertToImage();
314
            Refresh();
315
        }
316

    
317
        M_Scout::iterator it = scouts.begin();
318
        M_Scout::iterator end = scouts.end();
319

    
320
        world_state state;
321
        state.canvas_width = width_in_meters;
322
        state.canvas_height = height_in_meters;
323

    
324
        for (; it != end; ++it)
325
        {
326
            it->second->update(0.016, path_dc,
327
                               path_image, lines_image, walls_image,
328
                               path_dc.GetBackground().GetColour(),
329
                               state);
330
        }
331

    
332
        frame_count++;
333
    }
334

    
335
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
336
                                 std_srvs::Empty::Response&)
337
    {
338
        ROS_INFO("Clearing scoutsim.");
339
        clear();
340
        return true;
341
    }
342

    
343
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
344
                                 std_srvs::Empty::Response&)
345
    {
346
        ROS_INFO("Resetting scoutsim.");
347
        scouts.clear();
348
        id_counter = 0;
349
        spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0);
350
        clear();
351
        return true;
352
    }
353

    
354
    void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg)
355
    {
356
        wireless_receive.publish(msg);
357
    }
358
}