root / scout / scoutsim / src / sim_frame.cpp @ c06735bb
History | View | Annotate | Download (19.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(REAL_TIME_REFRESH_RATE * 1000);
|
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 |
map_base_name = ros::package::getPath("scoutsim") + "/maps/" + |
81 |
map_name + ".bmp";
|
82 |
map_lines_name = ros::package::getPath("scoutsim") + "/maps/" + |
83 |
map_name + "_lines.bmp";
|
84 |
map_walls_name = ros::package::getPath("scoutsim") + "/maps/" + |
85 |
map_name + "_walls.bmp";
|
86 |
display_map_name = map_base_name; |
87 |
|
88 |
wxBitmap lines_bitmap; |
89 |
wxBitmap walls_bitmap; |
90 |
path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str())); |
91 |
|
92 |
// Try to load the file; if it fails, make a new blank file
|
93 |
if (!lines_bitmap.LoadFile(wxString::FromAscii(map_lines_name.c_str())))
|
94 |
{ |
95 |
lines_bitmap = wxBitmap(path_bitmap.GetWidth(), path_bitmap.GetHeight(), 3);
|
96 |
} |
97 |
lines_image = lines_bitmap.ConvertToImage(); |
98 |
|
99 |
// Try to load the file; if it fails, make a new blank file
|
100 |
if (!walls_bitmap.LoadFile(wxString::FromAscii(map_walls_name.c_str())))
|
101 |
{ |
102 |
walls_bitmap = wxBitmap(path_bitmap.GetWidth(), path_bitmap.GetHeight(), 3);
|
103 |
} |
104 |
walls_image = walls_bitmap.ConvertToImage(); |
105 |
|
106 |
clear(); |
107 |
|
108 |
clear_srv = nh.advertiseService("clear",
|
109 |
&SimFrame::clearCallback, this);
|
110 |
reset_srv = nh.advertiseService("reset",
|
111 |
&SimFrame::resetCallback, this);
|
112 |
spawn_srv = nh.advertiseService("spawn",
|
113 |
&SimFrame::spawnCallback, this);
|
114 |
kill_srv = nh.advertiseService("kill",
|
115 |
&SimFrame::killCallback, this);
|
116 |
set_sonar_viz_srv = nh.advertiseService("set_sonar_viz",
|
117 |
&SimFrame::setSonarVizCallback, this);
|
118 |
set_ghost_srv = nh.advertiseService("set_ghost",
|
119 |
&SimFrame::setGhostCallback, this);
|
120 |
set_teleop_srv = nh.advertiseService("set_teleop",
|
121 |
&SimFrame::setTeleopCallback, this);
|
122 |
|
123 |
// Subscribe and publisher wirless from robots
|
124 |
wireless_receive = nh.advertise< ::messages::WirelessPacket>( |
125 |
"/wireless/receive", 1000); |
126 |
wireless_send = nh.subscribe("/wireless/send", 1000, |
127 |
&SimFrame::wirelessCallback, this);
|
128 |
|
129 |
// Teleop
|
130 |
teleop_type = TELEOP_OFF; |
131 |
teleop_l_speed = 0;
|
132 |
teleop_r_speed = 0;
|
133 |
teleop_scoutname = "scout1";
|
134 |
|
135 |
teleop_pub = nh.advertise<motors::set_motors>("/scout1/set_motors", 1000); |
136 |
|
137 |
ROS_INFO("Starting scoutsim with node name %s",
|
138 |
ros::this_node::getName().c_str()) ; |
139 |
|
140 |
wxMenu *menuFile = new wxMenu;
|
141 |
menuFile->Append(ID_ABOUT, _("&About"));
|
142 |
menuFile->AppendSeparator(); |
143 |
menuFile->Append(ID_QUIT, _("E&xit"));
|
144 |
|
145 |
wxMenu *menuSim = new wxMenu;
|
146 |
menuSim->Append(ID_CLEAR, _("&Clear"));
|
147 |
|
148 |
wxMenu *menuView = new wxMenu;
|
149 |
menuView->Append(ID_MAP, _("&Map"));
|
150 |
menuView->Append(ID_LINES, _("&Lines"));
|
151 |
menuView->Append(ID_WALLS, _("&Walls"));
|
152 |
|
153 |
wxMenu *menuTeleop = new wxMenu;
|
154 |
menuTeleop->Append(ID_TELEOP_NONE, _("&None"));
|
155 |
menuTeleop->Append(ID_TELEOP_PRECISE, _("&Precise"));
|
156 |
menuTeleop->Append(ID_TELEOP_FLUID, _("&Fluid"));
|
157 |
|
158 |
wxMenuBar *menuBar = new wxMenuBar;
|
159 |
menuBar->Append(menuFile, _("&File"));
|
160 |
menuBar->Append(menuSim, _("&Sim"));
|
161 |
menuBar->Append(menuView, _("&View"));
|
162 |
menuBar->Append(menuTeleop, _("&Teleop"));
|
163 |
|
164 |
SetMenuBar(menuBar); |
165 |
|
166 |
width_in_meters = GetSize().GetWidth() / PIX_PER_METER; |
167 |
height_in_meters = GetSize().GetHeight() / PIX_PER_METER; |
168 |
|
169 |
spawnScout("scout1", 1.4, .78, 0); |
170 |
} |
171 |
|
172 |
SimFrame::~SimFrame() |
173 |
{ |
174 |
delete update_timer;
|
175 |
} |
176 |
|
177 |
bool SimFrame::spawnCallback(scoutsim::Spawn::Request &req,
|
178 |
scoutsim::Spawn::Response &res) |
179 |
{ |
180 |
std::string name = spawnScout(req.name, req.x, req.y, req.theta);
|
181 |
if (name.empty())
|
182 |
{ |
183 |
ROS_WARN("A scout named [%s] already exists", req.name.c_str());
|
184 |
return false; |
185 |
} |
186 |
|
187 |
res.name = name; |
188 |
return true; |
189 |
} |
190 |
|
191 |
bool SimFrame::killCallback(scoutsim::Kill::Request& req,
|
192 |
scoutsim::Kill::Response&) |
193 |
{ |
194 |
M_Scout::iterator it = scouts.find(req.name); |
195 |
if (it == scouts.end())
|
196 |
{ |
197 |
ROS_WARN("Tried to kill scout [%s], which does not exist",
|
198 |
req.name.c_str()); |
199 |
return false; |
200 |
} |
201 |
|
202 |
scouts.erase(it); |
203 |
|
204 |
return true; |
205 |
} |
206 |
|
207 |
bool SimFrame::setSonarVizCallback(SetSonarViz::Request& req,
|
208 |
SetSonarViz::Response&) |
209 |
{ |
210 |
M_Scout::iterator it = scouts.find(req.scout_name); |
211 |
if (it == scouts.end())
|
212 |
{ |
213 |
ROS_WARN("Tried to set sonar on scout [%s], which does not exist",
|
214 |
req.scout_name.c_str()); |
215 |
return false; |
216 |
} |
217 |
|
218 |
it->second->set_sonar_visual(req.on); |
219 |
return true; |
220 |
} |
221 |
|
222 |
bool SimFrame::setGhostCallback(SetGhost::Request& req,
|
223 |
SetGhost::Response&) |
224 |
{ |
225 |
for (unsigned int i=0; i < ghost_scouts.size(); ++i) |
226 |
{ |
227 |
if (ghost_scouts.at(i)->get_name() == req.scout_name)
|
228 |
{ |
229 |
ghost_scouts.at(i)->set_visible(req.on); |
230 |
return true; |
231 |
} |
232 |
} |
233 |
|
234 |
ROS_WARN("Tried to set ghost on scout [%s], which does not exist",
|
235 |
req.scout_name.c_str()); |
236 |
return false; |
237 |
} |
238 |
|
239 |
bool SimFrame::setTeleopCallback(SetTeleop::Request& req,
|
240 |
SetTeleop::Response&) |
241 |
{ |
242 |
std::stringstream ss; |
243 |
ss << "/" << req.scout_name << "/set_motors"; |
244 |
teleop_pub = nh.advertise<motors::set_motors>(ss.str(), 1000);
|
245 |
teleop_scoutname = req.scout_name.c_str(); |
246 |
ROS_INFO("Teleoping %s...",teleop_scoutname.c_str()); //debug statement |
247 |
|
248 |
return true; |
249 |
} |
250 |
|
251 |
bool SimFrame::hasScout(const std::string& name) |
252 |
{ |
253 |
return scouts.find(name) != scouts.end();
|
254 |
} |
255 |
|
256 |
std::string SimFrame::spawnScout(const std::string& name, |
257 |
float x, float y, float angle) |
258 |
{ |
259 |
std::string real_name = name;
|
260 |
if (real_name.empty())
|
261 |
{ |
262 |
// Generate the name scoutX, where X is an increasing number.
|
263 |
do
|
264 |
{ |
265 |
std::stringstream ss; |
266 |
ss << "scout" << ++id_counter;
|
267 |
real_name = ss.str(); |
268 |
} |
269 |
while (hasScout(real_name));
|
270 |
} |
271 |
else
|
272 |
{ |
273 |
if (hasScout(real_name))
|
274 |
{ |
275 |
return ""; |
276 |
} |
277 |
} |
278 |
|
279 |
wxImage scout_image; |
280 |
|
281 |
// Try to load a name-specific image; if not, load the default scout
|
282 |
string specific_name = images_path + name + ".png"; |
283 |
if (fileExists(specific_name))
|
284 |
{ |
285 |
scout_image.LoadFile(wxString::FromAscii(specific_name.c_str())); |
286 |
scout_image.SetMask(true);
|
287 |
scout_image.SetMaskColour(255, 255, 255); |
288 |
} |
289 |
else
|
290 |
{ |
291 |
scout_image.LoadFile( |
292 |
wxString::FromAscii((images_path + "scout.png").c_str()));
|
293 |
scout_image.SetMask(true);
|
294 |
scout_image.SetMaskColour(255, 255, 255); |
295 |
} |
296 |
|
297 |
ScoutPtr t(new Scout(ros::NodeHandle(real_name),
|
298 |
scout_image, Vector2(x, y), &path_bitmap, angle)); |
299 |
scouts[real_name] = t; |
300 |
|
301 |
ghost_scouts.push_back(new GhostScout(ros::NodeHandle(real_name),
|
302 |
scout_image, Vector2(x, y), &path_bitmap, angle, name)); |
303 |
|
304 |
ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
|
305 |
real_name.c_str(), x, y, angle); |
306 |
|
307 |
return real_name;
|
308 |
} |
309 |
|
310 |
void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
|
311 |
{ |
312 |
Close(true);
|
313 |
} |
314 |
|
315 |
void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
|
316 |
{ |
317 |
wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
|
318 |
"\nThe Colony Project is a part of the Carnegie Mellon\n"
|
319 |
"Robotics Club. Our goal is to use cooperative low-cost\n"
|
320 |
"robots to solve challenging problems."),
|
321 |
_("About Scoutsim"),
|
322 |
wxOK | wxICON_INFORMATION, this );
|
323 |
} |
324 |
|
325 |
void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
|
326 |
{ |
327 |
clear(); |
328 |
} |
329 |
|
330 |
void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
|
331 |
{ |
332 |
display_map_name = map_base_name; |
333 |
clear(); |
334 |
} |
335 |
|
336 |
void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
|
337 |
{ |
338 |
display_map_name = map_lines_name; |
339 |
clear(); |
340 |
} |
341 |
|
342 |
void SimFrame::showWalls(wxCommandEvent& WXUNUSED(event))
|
343 |
{ |
344 |
display_map_name = map_walls_name; |
345 |
clear(); |
346 |
} |
347 |
|
348 |
void SimFrame::clear()
|
349 |
{ |
350 |
path_dc.SetBackground(wxBrush(wxColour(100, 100, 100))); |
351 |
path_dc.Clear(); |
352 |
|
353 |
sonar_dc.SetBackground(wxBrush(wxColour(255, 0, 0))); |
354 |
sonar_dc.Clear(); |
355 |
|
356 |
sonar_dc.SelectObject(path_bitmap); |
357 |
|
358 |
path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str())); |
359 |
path_dc.SelectObject(path_bitmap); |
360 |
SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight())); |
361 |
} |
362 |
|
363 |
// Runs every REAL_TIME_REFRESH_RATE.
|
364 |
void SimFrame::onUpdate(wxTimerEvent& evt)
|
365 |
{ |
366 |
ros::spinOnce(); |
367 |
|
368 |
teleop(); |
369 |
|
370 |
updateScouts(); |
371 |
|
372 |
if (!ros::ok())
|
373 |
{ |
374 |
Close(); |
375 |
} |
376 |
|
377 |
frame_count++; |
378 |
} |
379 |
|
380 |
void SimFrame::onPaint(wxPaintEvent& evt)
|
381 |
{ |
382 |
wxPaintDC dc(this);
|
383 |
|
384 |
dc.DrawBitmap(path_bitmap, 0, 0, true); |
385 |
|
386 |
M_Scout::iterator it = scouts.begin(); |
387 |
M_Scout::iterator end = scouts.end(); |
388 |
for (; it != end; ++it)
|
389 |
{ |
390 |
it->second->paint(dc); |
391 |
} |
392 |
for (unsigned int i=0; i < ghost_scouts.size(); ++i) |
393 |
{ |
394 |
ghost_scouts.at(i)->paint(dc); |
395 |
} |
396 |
} |
397 |
|
398 |
bool SimFrame::fileExists(const std::string& filename) |
399 |
{ |
400 |
struct stat buf;
|
401 |
if (stat(filename.c_str(), &buf) != -1) |
402 |
{ |
403 |
return true; |
404 |
} |
405 |
return false; |
406 |
} |
407 |
|
408 |
void SimFrame::stopTeleop(wxCommandEvent& event)
|
409 |
{ |
410 |
teleop_type = TELEOP_OFF; |
411 |
teleop_l_speed = 0;
|
412 |
teleop_r_speed = 0;
|
413 |
} |
414 |
|
415 |
void SimFrame::startTeleopPrecise(wxCommandEvent& event)
|
416 |
{ |
417 |
teleop_type = TELEOP_PRECISE; |
418 |
teleop_l_speed = 0;
|
419 |
teleop_r_speed = 0;
|
420 |
} |
421 |
|
422 |
void SimFrame::startTeleopFluid(wxCommandEvent& event)
|
423 |
{ |
424 |
teleop_type = TELEOP_FLUID; |
425 |
teleop_l_speed = 0;
|
426 |
teleop_r_speed = 0;
|
427 |
teleop_fluid_speed = 0;
|
428 |
teleop_fluid_omega = 0;
|
429 |
} |
430 |
|
431 |
void SimFrame::teleop_move_precise()
|
432 |
{ |
433 |
// Default to stop
|
434 |
teleop_l_speed = 0;
|
435 |
teleop_r_speed = 0;
|
436 |
|
437 |
if (wxGetKeyState(WXK_UP))
|
438 |
{ |
439 |
teleop_l_speed = TELEOP_PRECISE_SPEED; |
440 |
teleop_r_speed = TELEOP_PRECISE_SPEED; |
441 |
} |
442 |
else if (wxGetKeyState(WXK_DOWN)) |
443 |
{ |
444 |
teleop_l_speed = -TELEOP_PRECISE_SPEED; |
445 |
teleop_r_speed = -TELEOP_PRECISE_SPEED; |
446 |
} |
447 |
else if (wxGetKeyState(WXK_LEFT)) |
448 |
{ |
449 |
teleop_l_speed = -TELEOP_PRECISE_TURN_SPEED; |
450 |
teleop_r_speed = TELEOP_PRECISE_TURN_SPEED; |
451 |
} |
452 |
else if (wxGetKeyState(WXK_RIGHT)) |
453 |
{ |
454 |
teleop_l_speed = TELEOP_PRECISE_TURN_SPEED; |
455 |
teleop_r_speed = -TELEOP_PRECISE_TURN_SPEED; |
456 |
} |
457 |
} |
458 |
|
459 |
void SimFrame::teleop_move_fluid()
|
460 |
{ |
461 |
if (wxGetKeyState(WXK_UP))
|
462 |
{ |
463 |
teleop_fluid_speed += TELEOP_FLUID_INC * 2;
|
464 |
} |
465 |
else if (wxGetKeyState(WXK_DOWN)) |
466 |
{ |
467 |
teleop_fluid_speed -= TELEOP_FLUID_INC * 2;
|
468 |
} |
469 |
else if (teleop_fluid_speed > TELEOP_FLUID_INC) |
470 |
{ |
471 |
teleop_fluid_speed -= TELEOP_FLUID_INC; |
472 |
} |
473 |
else if (teleop_fluid_speed < -TELEOP_FLUID_INC) |
474 |
{ |
475 |
teleop_fluid_speed += TELEOP_FLUID_INC; |
476 |
} |
477 |
else
|
478 |
{ |
479 |
teleop_fluid_speed = 0;
|
480 |
} |
481 |
|
482 |
if (wxGetKeyState(WXK_LEFT))
|
483 |
{ |
484 |
teleop_fluid_omega -= TELEOP_FLUID_INC * 2;
|
485 |
} |
486 |
else if (wxGetKeyState(WXK_RIGHT)) |
487 |
{ |
488 |
teleop_fluid_omega += TELEOP_FLUID_INC * 2;
|
489 |
} |
490 |
else
|
491 |
{ |
492 |
teleop_fluid_omega = 0;
|
493 |
} |
494 |
|
495 |
if (teleop_fluid_speed > TELEOP_FLUID_MAX_SPEED)
|
496 |
{ |
497 |
teleop_fluid_speed = TELEOP_FLUID_MAX_SPEED; |
498 |
} |
499 |
else if (teleop_fluid_speed < -TELEOP_FLUID_MAX_SPEED) |
500 |
{ |
501 |
teleop_fluid_speed = -TELEOP_FLUID_MAX_SPEED; |
502 |
} |
503 |
if (teleop_fluid_omega > TELEOP_FLUID_MAX_SPEED)
|
504 |
{ |
505 |
teleop_fluid_omega = TELEOP_FLUID_MAX_SPEED; |
506 |
} |
507 |
else if (teleop_fluid_omega < -TELEOP_FLUID_MAX_SPEED) |
508 |
{ |
509 |
teleop_fluid_omega = -TELEOP_FLUID_MAX_SPEED; |
510 |
} |
511 |
|
512 |
int l_speed = teleop_fluid_speed + teleop_fluid_omega;
|
513 |
int r_speed = teleop_fluid_speed - teleop_fluid_omega;
|
514 |
|
515 |
teleop_l_speed = max(MIN_ABSOLUTE_SPEED, |
516 |
min(MAX_ABSOLUTE_SPEED, l_speed)); |
517 |
teleop_r_speed = max(MIN_ABSOLUTE_SPEED, |
518 |
min(MAX_ABSOLUTE_SPEED, r_speed)); |
519 |
} |
520 |
|
521 |
void SimFrame::teleop()
|
522 |
{ |
523 |
switch (teleop_type)
|
524 |
{ |
525 |
case TELEOP_OFF:
|
526 |
return;
|
527 |
case TELEOP_PRECISE:
|
528 |
teleop_move_precise(); |
529 |
break;
|
530 |
case TELEOP_FLUID:
|
531 |
teleop_move_fluid(); |
532 |
break;
|
533 |
} |
534 |
|
535 |
motors::set_motors msg; |
536 |
msg.fl_set = true;
|
537 |
msg.fr_set = true;
|
538 |
msg.bl_set = true;
|
539 |
msg.br_set = true;
|
540 |
msg.teleop_ON = true;
|
541 |
|
542 |
msg.fl_speed = teleop_l_speed; |
543 |
msg.fr_speed = teleop_r_speed; |
544 |
msg.bl_speed = teleop_l_speed; |
545 |
msg.br_speed = teleop_r_speed; |
546 |
|
547 |
teleop_pub.publish(msg); |
548 |
} |
549 |
|
550 |
void SimFrame::updateScouts()
|
551 |
{ |
552 |
std::string teleop_out = ""; |
553 |
|
554 |
if (last_scout_update.isZero())
|
555 |
{ |
556 |
last_scout_update = ros::WallTime::now(); |
557 |
return;
|
558 |
} |
559 |
|
560 |
path_image = path_bitmap.ConvertToImage(); |
561 |
Refresh(); |
562 |
|
563 |
M_Scout::iterator it = scouts.begin(); |
564 |
M_Scout::iterator end = scouts.end(); |
565 |
|
566 |
world_state state; |
567 |
state.canvas_width = width_in_meters; |
568 |
state.canvas_height = height_in_meters; |
569 |
|
570 |
for (; it != end; ++it)
|
571 |
{ |
572 |
|
573 |
//default to scout1
|
574 |
if (teleop_type != TELEOP_OFF)
|
575 |
{ |
576 |
teleop_out = teleop_scoutname; |
577 |
} |
578 |
|
579 |
it->second->update(SIM_TIME_REFRESH_RATE, |
580 |
path_dc, sonar_dc, |
581 |
path_image, lines_image, walls_image, |
582 |
path_dc.GetBackground().GetColour(), |
583 |
sonar_dc.GetBackground().GetColour(), |
584 |
state,teleop_out); |
585 |
} |
586 |
|
587 |
for (unsigned int i = 0; i < ghost_scouts.size(); ++i) |
588 |
{ |
589 |
ghost_scouts.at(i)->update(SIM_TIME_REFRESH_RATE, path_dc, sonar_dc, |
590 |
path_dc.GetBackground().GetColour(), state); |
591 |
} |
592 |
|
593 |
frame_count++; |
594 |
} |
595 |
|
596 |
bool SimFrame::clearCallback(std_srvs::Empty::Request&,
|
597 |
std_srvs::Empty::Response&) |
598 |
{ |
599 |
ROS_INFO("Clearing scoutsim.");
|
600 |
clear(); |
601 |
return true; |
602 |
} |
603 |
|
604 |
bool SimFrame::resetCallback(std_srvs::Empty::Request&,
|
605 |
std_srvs::Empty::Response&) |
606 |
{ |
607 |
ROS_INFO("Resetting scoutsim.");
|
608 |
scouts.clear(); |
609 |
id_counter = 0;
|
610 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
611 |
clear(); |
612 |
return true; |
613 |
} |
614 |
|
615 |
void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg) |
616 |
{ |
617 |
wireless_receive.publish(msg); |
618 |
} |
619 |
} |