root / scout / scoutsim / src / sim_frame.cpp @ 2eaafff2
History | View | Annotate | Download (10.1 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 |
base_map_name = map_name; |
96 |
display_map_name = ros::package::getPath("scoutsim") + "/maps/" + map_name + ".bmp"; |
97 |
clear(); |
98 |
|
99 |
clear_srv = nh.advertiseService("clear",
|
100 |
&SimFrame::clearCallback, this);
|
101 |
reset_srv = nh.advertiseService("reset",
|
102 |
&SimFrame::resetCallback, this);
|
103 |
spawn_srv = nh.advertiseService("spawn",
|
104 |
&SimFrame::spawnCallback, this);
|
105 |
kill_srv = nh.advertiseService("kill",
|
106 |
&SimFrame::killCallback, this);
|
107 |
|
108 |
ROS_INFO("Starting scoutsim with node name %s",
|
109 |
ros::this_node::getName().c_str()) ; |
110 |
|
111 |
wxMenu *menuFile = new wxMenu;
|
112 |
menuFile->Append(ID_ABOUT, _("&About"));
|
113 |
menuFile->AppendSeparator(); |
114 |
menuFile->Append(ID_QUIT, _("E&xit"));
|
115 |
|
116 |
wxMenu *menuSim = new wxMenu;
|
117 |
menuSim->Append(ID_CLEAR, _("&Clear"));
|
118 |
|
119 |
wxMenu *menuView = new wxMenu;
|
120 |
menuView->Append(ID_MAP, _("&Map"));
|
121 |
menuView->Append(ID_LINES, _("&Lines"));
|
122 |
|
123 |
wxMenuBar *menuBar = new wxMenuBar;
|
124 |
menuBar->Append(menuFile, _("&File"));
|
125 |
menuBar->Append(menuSim, _("&Sim"));
|
126 |
menuBar->Append(menuView, _("&View"));
|
127 |
|
128 |
SetMenuBar(menuBar); |
129 |
|
130 |
width_in_meters = GetSize().GetWidth() / meter; |
131 |
height_in_meters = GetSize().GetHeight() / meter; |
132 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
133 |
} |
134 |
|
135 |
SimFrame::~SimFrame() |
136 |
{ |
137 |
delete update_timer;
|
138 |
} |
139 |
|
140 |
bool SimFrame::spawnCallback(scoutsim::Spawn::Request &req,
|
141 |
scoutsim::Spawn::Response &res) |
142 |
{ |
143 |
std::string name = spawnScout(req.name, req.x, req.y, req.theta);
|
144 |
if (name.empty())
|
145 |
{ |
146 |
ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
|
147 |
return false; |
148 |
} |
149 |
|
150 |
res.name = name; |
151 |
|
152 |
return true; |
153 |
} |
154 |
|
155 |
bool SimFrame::killCallback(scoutsim::Kill::Request& req,
|
156 |
scoutsim::Kill::Response&) |
157 |
{ |
158 |
M_Scout::iterator it = scouts.find(req.name); |
159 |
if (it == scouts.end())
|
160 |
{ |
161 |
ROS_ERROR("Tried to kill scout [%s], which does not exist",
|
162 |
req.name.c_str()); |
163 |
return false; |
164 |
} |
165 |
|
166 |
scouts.erase(it); |
167 |
|
168 |
return true; |
169 |
} |
170 |
|
171 |
bool SimFrame::hasScout(const std::string& name) |
172 |
{ |
173 |
return scouts.find(name) != scouts.end();
|
174 |
} |
175 |
|
176 |
std::string SimFrame::spawnScout(const std::string& name, |
177 |
float x, float y, float angle) |
178 |
{ |
179 |
std::string real_name = name;
|
180 |
if (real_name.empty())
|
181 |
{ |
182 |
do
|
183 |
{ |
184 |
std::stringstream ss; |
185 |
ss << "scout" << ++id_counter;
|
186 |
real_name = ss.str(); |
187 |
} while (hasScout(real_name));
|
188 |
} |
189 |
else
|
190 |
{ |
191 |
if (hasScout(real_name))
|
192 |
{ |
193 |
return ""; |
194 |
} |
195 |
} |
196 |
|
197 |
ScoutPtr t(new Scout(ros::NodeHandle(real_name),
|
198 |
scout_images[rand() % SCOUTSIM_NUM_SCOUTS], |
199 |
Vector2(x, y), angle)); |
200 |
scouts[real_name] = t; |
201 |
|
202 |
ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
|
203 |
real_name.c_str(), x, y, angle); |
204 |
|
205 |
return real_name;
|
206 |
} |
207 |
|
208 |
void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
|
209 |
{ |
210 |
Close(true);
|
211 |
} |
212 |
|
213 |
void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
|
214 |
{ |
215 |
wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
|
216 |
"\nThe Colony Project is a part of the Carnegie Mellon\n"
|
217 |
"Robotics Club. Our goal is to use cooperative low-cost\n"
|
218 |
"robots to solve challenging problems."),
|
219 |
_("About Scoutsim"),
|
220 |
wxOK | wxICON_INFORMATION, this );
|
221 |
} |
222 |
|
223 |
void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
|
224 |
{ |
225 |
clear(); |
226 |
} |
227 |
|
228 |
void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
|
229 |
{ |
230 |
display_map_name = ros::package::getPath("scoutsim") + "/maps/" + |
231 |
base_map_name + ".bmp";
|
232 |
clear(); |
233 |
} |
234 |
|
235 |
void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
|
236 |
{ |
237 |
display_map_name = ros::package::getPath("scoutsim") + "/maps/" + |
238 |
base_map_name + "_lines.bmp";
|
239 |
clear(); |
240 |
} |
241 |
|
242 |
void SimFrame::clear()
|
243 |
{ |
244 |
path_dc.SetBackground(wxBrush(wxColour(100, 100, 100))); |
245 |
path_dc.Clear(); |
246 |
|
247 |
path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str())); |
248 |
path_dc.SelectObject(path_bitmap); |
249 |
SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight())); |
250 |
} |
251 |
|
252 |
void SimFrame::onUpdate(wxTimerEvent& evt)
|
253 |
{ |
254 |
ros::spinOnce(); |
255 |
|
256 |
updateScouts(); |
257 |
|
258 |
if (!ros::ok())
|
259 |
{ |
260 |
Close(); |
261 |
} |
262 |
} |
263 |
|
264 |
void SimFrame::onPaint(wxPaintEvent& evt)
|
265 |
{ |
266 |
wxPaintDC dc(this);
|
267 |
|
268 |
dc.DrawBitmap(path_bitmap, 0, 0, true); |
269 |
|
270 |
M_Scout::iterator it = scouts.begin(); |
271 |
M_Scout::iterator end = scouts.end(); |
272 |
for (; it != end; ++it)
|
273 |
{ |
274 |
it->second->paint(dc); |
275 |
} |
276 |
} |
277 |
|
278 |
void SimFrame::updateScouts()
|
279 |
{ |
280 |
if (last_scout_update.isZero())
|
281 |
{ |
282 |
last_scout_update = ros::WallTime::now(); |
283 |
return;
|
284 |
} |
285 |
|
286 |
if (frame_count % 3 == 0) |
287 |
{ |
288 |
path_image = path_bitmap.ConvertToImage(); |
289 |
Refresh(); |
290 |
} |
291 |
|
292 |
M_Scout::iterator it = scouts.begin(); |
293 |
M_Scout::iterator end = scouts.end(); |
294 |
|
295 |
world_state state; |
296 |
state.canvas_width = width_in_meters; |
297 |
state.canvas_height = height_in_meters; |
298 |
|
299 |
for (; it != end; ++it)
|
300 |
{ |
301 |
it->second->update(0.016, path_dc, path_image, |
302 |
path_dc.GetBackground().GetColour(), |
303 |
state); |
304 |
} |
305 |
|
306 |
frame_count++; |
307 |
} |
308 |
|
309 |
bool SimFrame::clearCallback(std_srvs::Empty::Request&,
|
310 |
std_srvs::Empty::Response&) |
311 |
{ |
312 |
ROS_INFO("Clearing scoutsim.");
|
313 |
clear(); |
314 |
return true; |
315 |
} |
316 |
|
317 |
bool SimFrame::resetCallback(std_srvs::Empty::Request&,
|
318 |
std_srvs::Empty::Response&) |
319 |
{ |
320 |
ROS_INFO("Resetting scoutsim.");
|
321 |
scouts.clear(); |
322 |
id_counter = 0;
|
323 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
324 |
clear(); |
325 |
return true; |
326 |
} |
327 |
|
328 |
} |