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