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