scoutos / scout / scoutsim / src / sim_frame.cpp @ 594c3bb9
History | View | Annotate | Download (16.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 |
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 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
166 |
} |
167 |
|
168 |
SimFrame::~SimFrame() |
169 |
{ |
170 |
delete update_timer;
|
171 |
} |
172 |
|
173 |
bool SimFrame::spawnCallback(scoutsim::Spawn::Request &req,
|
174 |
scoutsim::Spawn::Response &res) |
175 |
{ |
176 |
std::string name = spawnScout(req.name, req.x, req.y, req.theta);
|
177 |
if (name.empty())
|
178 |
{ |
179 |
ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
|
180 |
return false; |
181 |
} |
182 |
|
183 |
res.name = name; |
184 |
|
185 |
return true; |
186 |
} |
187 |
|
188 |
bool SimFrame::killCallback(scoutsim::Kill::Request& req,
|
189 |
scoutsim::Kill::Response&) |
190 |
{ |
191 |
M_Scout::iterator it = scouts.find(req.name); |
192 |
if (it == scouts.end())
|
193 |
{ |
194 |
ROS_ERROR("Tried to kill scout [%s], which does not exist",
|
195 |
req.name.c_str()); |
196 |
return false; |
197 |
} |
198 |
|
199 |
scouts.erase(it); |
200 |
|
201 |
return true; |
202 |
} |
203 |
|
204 |
bool SimFrame::hasScout(const std::string& name) |
205 |
{ |
206 |
return scouts.find(name) != scouts.end();
|
207 |
} |
208 |
|
209 |
std::string SimFrame::spawnScout(const std::string& name, |
210 |
float x, float y, float angle) |
211 |
{ |
212 |
std::string real_name = name;
|
213 |
if (real_name.empty())
|
214 |
{ |
215 |
do
|
216 |
{ |
217 |
std::stringstream ss; |
218 |
ss << "scout" << ++id_counter;
|
219 |
real_name = ss.str(); |
220 |
} while (hasScout(real_name));
|
221 |
} |
222 |
else
|
223 |
{ |
224 |
if (hasScout(real_name))
|
225 |
{ |
226 |
return ""; |
227 |
} |
228 |
} |
229 |
|
230 |
wxImage scout_image; |
231 |
|
232 |
// Try to load a name-specific image; if not, load the default scout
|
233 |
string specific_name = images_path + name + ".png"; |
234 |
if (fileExists(specific_name))
|
235 |
{ |
236 |
scout_image.LoadFile(wxString::FromAscii(specific_name.c_str())); |
237 |
scout_image.SetMask(true);
|
238 |
scout_image.SetMaskColour(255, 255, 255); |
239 |
} |
240 |
else
|
241 |
{ |
242 |
scout_image.LoadFile( |
243 |
wxString::FromAscii((images_path + "scout.png").c_str()));
|
244 |
scout_image.SetMask(true);
|
245 |
scout_image.SetMaskColour(255, 255, 255); |
246 |
} |
247 |
|
248 |
ScoutPtr t(new Scout(ros::NodeHandle(real_name),
|
249 |
scout_image, Vector2(x, y), &path_bitmap, angle)); |
250 |
scouts[real_name] = t; |
251 |
|
252 |
ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
|
253 |
real_name.c_str(), x, y, angle); |
254 |
|
255 |
return real_name;
|
256 |
} |
257 |
|
258 |
void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
|
259 |
{ |
260 |
Close(true);
|
261 |
} |
262 |
|
263 |
void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
|
264 |
{ |
265 |
wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
|
266 |
"\nThe Colony Project is a part of the Carnegie Mellon\n"
|
267 |
"Robotics Club. Our goal is to use cooperative low-cost\n"
|
268 |
"robots to solve challenging problems."),
|
269 |
_("About Scoutsim"),
|
270 |
wxOK | wxICON_INFORMATION, this );
|
271 |
} |
272 |
|
273 |
void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
|
274 |
{ |
275 |
clear(); |
276 |
} |
277 |
|
278 |
void SimFrame::showSonar(wxCommandEvent& WXUNUSED(event))
|
279 |
{ |
280 |
sonar_on = not sonar_on;
|
281 |
clear(); |
282 |
} |
283 |
|
284 |
|
285 |
void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
|
286 |
{ |
287 |
display_map_name = map_base_name; |
288 |
clear(); |
289 |
} |
290 |
|
291 |
void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
|
292 |
{ |
293 |
display_map_name = map_lines_name; |
294 |
clear(); |
295 |
} |
296 |
|
297 |
void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
|
298 |
{ |
299 |
display_map_name = map_walls_name; |
300 |
clear(); |
301 |
} |
302 |
|
303 |
void SimFrame::clear()
|
304 |
{ |
305 |
path_dc.SetBackground(wxBrush(wxColour(100, 100, 100))); |
306 |
path_dc.Clear(); |
307 |
|
308 |
sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0))); |
309 |
sonar_dc.Clear(); |
310 |
|
311 |
sonar_dc.SelectObject(path_bitmap); |
312 |
|
313 |
path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str())); |
314 |
path_dc.SelectObject(path_bitmap); |
315 |
SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight())); |
316 |
} |
317 |
|
318 |
void SimFrame::onUpdate(wxTimerEvent& evt)
|
319 |
{ |
320 |
ros::spinOnce(); |
321 |
|
322 |
teleop(); |
323 |
|
324 |
updateScouts(); |
325 |
|
326 |
if (!ros::ok())
|
327 |
{ |
328 |
Close(); |
329 |
} |
330 |
} |
331 |
|
332 |
void SimFrame::onPaint(wxPaintEvent& evt)
|
333 |
{ |
334 |
wxPaintDC dc(this);
|
335 |
|
336 |
dc.DrawBitmap(path_bitmap, 0, 0, true); |
337 |
|
338 |
M_Scout::iterator it = scouts.begin(); |
339 |
M_Scout::iterator end = scouts.end(); |
340 |
for (; it != end; ++it)
|
341 |
{ |
342 |
it->second->paint(dc); |
343 |
} |
344 |
} |
345 |
|
346 |
bool SimFrame::fileExists(const std::string& filename) |
347 |
{ |
348 |
struct stat buf;
|
349 |
if (stat(filename.c_str(), &buf) != -1) |
350 |
{ |
351 |
return true; |
352 |
} |
353 |
return false; |
354 |
} |
355 |
|
356 |
void SimFrame::stopTeleop(wxCommandEvent& event)
|
357 |
{ |
358 |
teleop_type = TELEOP_OFF; |
359 |
teleop_l_speed = 0;
|
360 |
teleop_r_speed = 0;
|
361 |
} |
362 |
|
363 |
void SimFrame::startTeleopPrecise(wxCommandEvent& event)
|
364 |
{ |
365 |
teleop_type = TELEOP_PRECISE; |
366 |
teleop_l_speed = 0;
|
367 |
teleop_r_speed = 0;
|
368 |
} |
369 |
|
370 |
void SimFrame::startTeleopFluid(wxCommandEvent& event)
|
371 |
{ |
372 |
teleop_type = TELEOP_FLUID; |
373 |
teleop_l_speed = 0;
|
374 |
teleop_r_speed = 0;
|
375 |
teleop_fluid_speed = 0;
|
376 |
teleop_fluid_omega = 0;
|
377 |
} |
378 |
|
379 |
void SimFrame::teleop_move_precise()
|
380 |
{ |
381 |
// Default to stop
|
382 |
teleop_l_speed = 0;
|
383 |
teleop_r_speed = 0;
|
384 |
|
385 |
if (wxGetKeyState(WXK_UP))
|
386 |
{ |
387 |
teleop_l_speed = TELEOP_PRECISE_SPEED; |
388 |
teleop_r_speed = TELEOP_PRECISE_SPEED; |
389 |
} |
390 |
else if (wxGetKeyState(WXK_DOWN)) |
391 |
{ |
392 |
teleop_l_speed = -TELEOP_PRECISE_SPEED; |
393 |
teleop_r_speed = -TELEOP_PRECISE_SPEED; |
394 |
} |
395 |
else if (wxGetKeyState(WXK_LEFT)) |
396 |
{ |
397 |
teleop_l_speed = -TELEOP_PRECISE_SPEED; |
398 |
teleop_r_speed = TELEOP_PRECISE_SPEED; |
399 |
} |
400 |
else if (wxGetKeyState(WXK_RIGHT)) |
401 |
{ |
402 |
teleop_l_speed = TELEOP_PRECISE_SPEED; |
403 |
teleop_r_speed = -TELEOP_PRECISE_SPEED; |
404 |
} |
405 |
} |
406 |
|
407 |
void SimFrame::teleop_move_fluid()
|
408 |
{ |
409 |
if (wxGetKeyState(WXK_UP))
|
410 |
{ |
411 |
teleop_fluid_speed += 2;
|
412 |
} |
413 |
else if (wxGetKeyState(WXK_DOWN)) |
414 |
{ |
415 |
teleop_fluid_speed -= 2;
|
416 |
} |
417 |
else if (teleop_fluid_speed > 0) |
418 |
{ |
419 |
teleop_fluid_speed -= 1;
|
420 |
} |
421 |
else if (teleop_fluid_speed < 0) |
422 |
{ |
423 |
teleop_fluid_speed += 1;
|
424 |
} |
425 |
|
426 |
if (wxGetKeyState(WXK_LEFT))
|
427 |
{ |
428 |
teleop_fluid_omega -= 1;
|
429 |
} |
430 |
else if (wxGetKeyState(WXK_RIGHT)) |
431 |
{ |
432 |
teleop_fluid_omega += 1;
|
433 |
} |
434 |
else if (teleop_fluid_omega > 0) |
435 |
{ |
436 |
teleop_fluid_omega -= 1;
|
437 |
} |
438 |
else if (teleop_fluid_omega < 0) |
439 |
{ |
440 |
teleop_fluid_omega += 1;
|
441 |
} |
442 |
|
443 |
if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
|
444 |
{ |
445 |
teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED; |
446 |
} |
447 |
if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED / 2) |
448 |
{ |
449 |
teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED / 2;
|
450 |
} |
451 |
|
452 |
teleop_l_speed = teleop_fluid_speed + teleop_fluid_omega; |
453 |
teleop_r_speed = teleop_fluid_speed - teleop_fluid_omega; |
454 |
} |
455 |
|
456 |
void SimFrame::teleop()
|
457 |
{ |
458 |
switch (teleop_type)
|
459 |
{ |
460 |
case TELEOP_OFF:
|
461 |
return;
|
462 |
case TELEOP_PRECISE:
|
463 |
teleop_move_precise(); |
464 |
break;
|
465 |
case TELEOP_FLUID:
|
466 |
teleop_move_fluid(); |
467 |
break;
|
468 |
} |
469 |
|
470 |
motors::set_motors msg; |
471 |
msg.fl_set = true;
|
472 |
msg.fr_set = true;
|
473 |
msg.bl_set = true;
|
474 |
msg.br_set = true;
|
475 |
|
476 |
msg.fl_speed = teleop_l_speed; |
477 |
msg.fr_speed = teleop_r_speed; |
478 |
msg.bl_speed = teleop_l_speed; |
479 |
msg.br_speed = teleop_r_speed; |
480 |
|
481 |
teleop_pub.publish(msg); |
482 |
} |
483 |
|
484 |
void SimFrame::updateScouts()
|
485 |
{ |
486 |
if (last_scout_update.isZero())
|
487 |
{ |
488 |
last_scout_update = ros::WallTime::now(); |
489 |
return;
|
490 |
} |
491 |
|
492 |
if (frame_count % 3 == 0) |
493 |
{ |
494 |
path_image = path_bitmap.ConvertToImage(); |
495 |
Refresh(); |
496 |
} |
497 |
|
498 |
M_Scout::iterator it = scouts.begin(); |
499 |
M_Scout::iterator end = scouts.end(); |
500 |
|
501 |
world_state state; |
502 |
state.canvas_width = width_in_meters; |
503 |
state.canvas_height = height_in_meters; |
504 |
|
505 |
for (; it != end; ++it)
|
506 |
{ |
507 |
it->second->update(0.016, path_dc,sonar_dc,sonar_on, |
508 |
path_image, lines_image, walls_image, |
509 |
path_dc.GetBackground().GetColour(), |
510 |
sonar_dc.GetBackground().GetColour(), |
511 |
state); |
512 |
} |
513 |
|
514 |
frame_count++; |
515 |
} |
516 |
|
517 |
bool SimFrame::clearCallback(std_srvs::Empty::Request&,
|
518 |
std_srvs::Empty::Response&) |
519 |
{ |
520 |
ROS_INFO("Clearing scoutsim.");
|
521 |
clear(); |
522 |
return true; |
523 |
} |
524 |
|
525 |
bool SimFrame::resetCallback(std_srvs::Empty::Request&,
|
526 |
std_srvs::Empty::Response&) |
527 |
{ |
528 |
ROS_INFO("Resetting scoutsim.");
|
529 |
scouts.clear(); |
530 |
id_counter = 0;
|
531 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
532 |
clear(); |
533 |
return true; |
534 |
} |
535 |
|
536 |
void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg) |
537 |
{ |
538 |
wireless_receive.publish(msg); |
539 |
} |
540 |
} |