scoutos / scout / scoutsim / src / scout.cpp @ 98ed4757
History | View | Annotate | Download (19.6 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 scout.cpp
|
50 |
*
|
51 |
* @ingroup scoutsim
|
52 |
* @{
|
53 |
*/
|
54 |
|
55 |
#include "scout.h" |
56 |
|
57 |
#include <wx/wx.h> |
58 |
|
59 |
#define DEFAULT_PEN_R 0xb3 |
60 |
#define DEFAULT_PEN_G 0xb8 |
61 |
#define DEFAULT_PEN_B 0xff |
62 |
|
63 |
using namespace std; |
64 |
|
65 |
namespace scoutsim
|
66 |
{ |
67 |
/**
|
68 |
* The scout object, which is responsible for refreshing itself and
|
69 |
* updating its position and simulated sensors.
|
70 |
*
|
71 |
* @ingroup scoutsim
|
72 |
*/
|
73 |
Scout::Scout(const ros::NodeHandle& nh,
|
74 |
const wxImage& scout_image,
|
75 |
const Vector2& pos,
|
76 |
wxBitmap *path_bitmap, |
77 |
float orient)
|
78 |
: path_bitmap(path_bitmap) |
79 |
, sonar_visual_on(false)
|
80 |
, sonar_on(true)
|
81 |
, ignore_behavior(false)
|
82 |
, node (nh) |
83 |
, scout_image(scout_image) |
84 |
, pos(pos) |
85 |
, orient(orient) |
86 |
, motor_fl_speed(0)
|
87 |
, motor_fr_speed(0)
|
88 |
, motor_bl_speed(0)
|
89 |
, motor_br_speed(0)
|
90 |
, fl_ticks(0)
|
91 |
, fr_ticks(0)
|
92 |
, bl_ticks(0)
|
93 |
, br_ticks(0)
|
94 |
, pen_on(true)
|
95 |
, pen(wxColour(DEFAULT_PEN_R, DEFAULT_PEN_G, DEFAULT_PEN_B)) |
96 |
{ |
97 |
pen.SetWidth(3);
|
98 |
scout = wxBitmap(scout_image); |
99 |
|
100 |
motors_sub = node.subscribe("set_motors", 1, &Scout::setMotors, this); |
101 |
|
102 |
pose_pub = node.advertise<Pose>("pose", 1); |
103 |
color_pub = node.advertise<Color>("color_sensor", 1); |
104 |
sonar_pub = node.advertise< ::messages::sonar_distance>("sonar_distance", 1); |
105 |
bom_pub = node.advertise<BOM>("BOM", 1); |
106 |
set_pen_srv = node.advertiseService("set_pen",
|
107 |
&Scout::setPenCallback, |
108 |
this);
|
109 |
toggle_sonar_srv = node.advertiseService("sonar_toggle",
|
110 |
&Scout::handle_sonar_toggle, |
111 |
this);
|
112 |
set_sonar_srv = node.advertiseService("sonar_set_scan",
|
113 |
&Scout::handle_sonar_set_scan, |
114 |
this);
|
115 |
query_encoders_srv = |
116 |
node.advertiseService("query_encoders",
|
117 |
&Scout::query_encoders_callback, |
118 |
this);
|
119 |
|
120 |
query_linesensor_srv = |
121 |
node.advertiseService("query_linesensor",
|
122 |
&Scout::query_linesensor_callback, |
123 |
this);
|
124 |
|
125 |
for (unsigned int i = 0; i < NUM_LINESENSORS; i++) |
126 |
{ |
127 |
linesensor_readings.push_back(0);
|
128 |
} |
129 |
|
130 |
// Initialize sonar
|
131 |
sonar_position = 0;
|
132 |
sonar_stop_l = 0;
|
133 |
sonar_stop_r = 23;
|
134 |
sonar_direction = 1;
|
135 |
sonar_tick_time = ros::Duration(scoutsim::SONAR_HALF_SPIN_TIME / 24.0); |
136 |
|
137 |
// Init latch
|
138 |
teleop_latch = 0;
|
139 |
} |
140 |
|
141 |
float Scout::absolute_to_mps(int absolute_speed) |
142 |
{ |
143 |
return ((float) absolute_speed) * MAX_SPEED_MPS / MAX_ABSOLUTE_SPEED; |
144 |
} |
145 |
|
146 |
/**
|
147 |
* A callback function that sets velocity based on a set_motors
|
148 |
* request.
|
149 |
* @todo Use "callback" in all callback function names? Or remove?
|
150 |
*/
|
151 |
void Scout::setMotors(const ::messages::set_motors::ConstPtr& msg) |
152 |
{ |
153 |
last_command_time = ros::WallTime::now(); |
154 |
|
155 |
//ignore non-teleop commands if commands if teleop is ON
|
156 |
//if (node.getNamespace() != current_teleop_scout || msg->teleop_ON)
|
157 |
//{
|
158 |
|
159 |
//latch value indicates number of uninterrupted teleop messages
|
160 |
//before teleop latch shifts again
|
161 |
if (!(msg->teleop_ON) && teleop_latch < 3) |
162 |
{ |
163 |
teleop_latch++; |
164 |
} |
165 |
|
166 |
if (!(msg->teleop_ON) || teleop_latch ==0) |
167 |
{ |
168 |
if(msg->fl_set)
|
169 |
{ |
170 |
motor_fl_speed = absolute_to_mps(msg->fl_speed); |
171 |
} |
172 |
if(msg->fr_set)
|
173 |
{ |
174 |
motor_fr_speed = absolute_to_mps(msg->fr_speed); |
175 |
} |
176 |
if(msg->bl_set)
|
177 |
{ |
178 |
motor_bl_speed = absolute_to_mps(msg->bl_speed); |
179 |
} |
180 |
if(msg->br_set)
|
181 |
{ |
182 |
motor_br_speed = absolute_to_mps(msg->br_speed); |
183 |
} |
184 |
} |
185 |
|
186 |
//if a teleop message comes through, decrease the latch
|
187 |
//latch code works on the assumption there will be more behavior messages
|
188 |
//than teleop messages
|
189 |
if (msg->teleop_ON && teleop_latch>0) |
190 |
{ |
191 |
teleop_latch--; |
192 |
} |
193 |
//}
|
194 |
|
195 |
} |
196 |
|
197 |
bool Scout::handle_sonar_toggle(::messages::sonar_toggle::Request &req,
|
198 |
::messages::sonar_toggle::Response &res) |
199 |
{ |
200 |
if (req.set_on && !sonar_on)
|
201 |
{ |
202 |
ROS_INFO("Turning on the sonar");
|
203 |
sonar_on = true;
|
204 |
|
205 |
} |
206 |
else if (!req.set_on && sonar_on) |
207 |
{ |
208 |
ROS_INFO("Turning off the sonar");
|
209 |
sonar_on = false;
|
210 |
} |
211 |
else
|
212 |
{ |
213 |
ROS_INFO("Sonar state remains unchanged");
|
214 |
} |
215 |
res.ack = true;
|
216 |
return true; |
217 |
} |
218 |
|
219 |
bool Scout::handle_sonar_set_scan(::messages::sonar_set_scan::Request &req,
|
220 |
::messages::sonar_set_scan::Response &res) |
221 |
{ |
222 |
// Code to set the sonar to scan from
|
223 |
// req.stop_l to req.stop_r
|
224 |
if (req.stop_l>=0 and req.stop_r<=23 and req.stop_l<=req.stop_r) |
225 |
{ |
226 |
ROS_INFO("Setting sonar scan range to [%i, %i]",
|
227 |
req.stop_l, |
228 |
req.stop_r); |
229 |
sonar_stop_l = req.stop_l; |
230 |
sonar_stop_r = req.stop_r; |
231 |
sonar_position = req.stop_l; |
232 |
sonar_direction = 1;
|
233 |
res.ack = true;
|
234 |
} |
235 |
else
|
236 |
{ |
237 |
ROS_INFO("Bad Input: Input should be integers 0-23, stop_l<stop_r");
|
238 |
} |
239 |
return true; |
240 |
} |
241 |
|
242 |
bool Scout::setPenCallback(scoutsim::SetPen::Request& req,
|
243 |
scoutsim::SetPen::Response&) |
244 |
{ |
245 |
pen_on = !req.off; |
246 |
if (req.off)
|
247 |
{ |
248 |
return true; |
249 |
} |
250 |
|
251 |
wxPen pen(wxColour(req.r, req.g, req.b)); |
252 |
if (req.width != 0) |
253 |
{ |
254 |
pen.SetWidth(req.width); |
255 |
} |
256 |
|
257 |
pen = pen; |
258 |
return true; |
259 |
} |
260 |
|
261 |
bool Scout::query_encoders_callback(::messages::query_encoders::Request&,
|
262 |
::messages::query_encoders::Response& res) |
263 |
{ |
264 |
res.fl_distance = fl_ticks; |
265 |
res.fr_distance = fr_ticks; |
266 |
res.bl_distance = bl_ticks; |
267 |
res.br_distance = br_ticks; |
268 |
|
269 |
return true; |
270 |
} |
271 |
|
272 |
bool Scout::query_linesensor_callback(::messages::query_linesensor::Request&,
|
273 |
::messages::query_linesensor::Response& res) |
274 |
{ |
275 |
res.readings = linesensor_readings; |
276 |
|
277 |
return true; |
278 |
} |
279 |
|
280 |
// Scale to linesensor value
|
281 |
unsigned int Scout::rgb_to_grey(unsigned char r, |
282 |
unsigned char g, |
283 |
unsigned char b) |
284 |
{ |
285 |
// Should be 0 to 255
|
286 |
unsigned int grey = ((unsigned int) r + (unsigned int) g + (unsigned int) b) / 3; |
287 |
|
288 |
/// @todo Convert to the proper range
|
289 |
return 255 - grey; |
290 |
} |
291 |
|
292 |
unsigned int Scout::trace_sonar(const wxImage& walls_image, int x, int y, |
293 |
double robot_theta, int sonar_pos, |
294 |
wxMemoryDC& sonar_dc) |
295 |
{ |
296 |
double angle = robot_theta + (PI * ((float) sonar_pos) / 24.0) - PI / 2; |
297 |
unsigned int d = 0; |
298 |
|
299 |
unsigned int reading = 0; |
300 |
|
301 |
int d_x = 0; |
302 |
int d_y = 0; |
303 |
|
304 |
do
|
305 |
{ |
306 |
d_x = x + (int) floor(d * cos(angle));
|
307 |
d_y = y - (int) floor(d * sin(angle));
|
308 |
|
309 |
// Out of image boundary
|
310 |
if (d_x < 0 || d_x >= walls_image.GetWidth() || |
311 |
d_y < 0 || d_y >= walls_image.GetHeight())
|
312 |
{ |
313 |
break;
|
314 |
} |
315 |
|
316 |
// Max range
|
317 |
if (d > scoutsim::SONAR_MAX_RANGE_PIX)
|
318 |
{ |
319 |
break;
|
320 |
} |
321 |
|
322 |
// Get the sonar reading at the current position of the sonar
|
323 |
unsigned char r = walls_image.GetRed(d_x, d_y); |
324 |
unsigned char g = walls_image.GetGreen(d_x, d_y); |
325 |
unsigned char b = walls_image.GetBlue(d_x, d_y); |
326 |
|
327 |
reading = rgb_to_grey(r, g, b); |
328 |
|
329 |
d++; |
330 |
} |
331 |
/// @todo Consider using different cutoffs for different features
|
332 |
while (reading < 128); /// @todo Get rid of hardcoded stuff like this |
333 |
|
334 |
if (sonar_visual_on)
|
335 |
{ |
336 |
if (isFront)
|
337 |
{ |
338 |
// draw a circle at the wall_x, wall_y where reading > 128
|
339 |
sonar_dc.SelectObject(*path_bitmap); |
340 |
sonar_dc.SetBrush(*wxRED_BRUSH); //old value
|
341 |
sonar_dc.DrawCircle(wxPoint(old_front_dx, old_front_dy), 2);
|
342 |
old_front_dx = d_x; |
343 |
old_front_dy = d_y; |
344 |
} |
345 |
else
|
346 |
{ |
347 |
// draw a circle at the wall_x, wall_y where reading > 128
|
348 |
sonar_dc.SelectObject(*path_bitmap); |
349 |
sonar_dc.SetBrush(*wxRED_BRUSH); //old value
|
350 |
sonar_dc.DrawCircle(wxPoint(old_back_dx,old_back_dy), 2);
|
351 |
old_back_dx = d_x; |
352 |
old_back_dy = d_y; |
353 |
} |
354 |
|
355 |
sonar_dc.SetBrush(*wxGREEN_BRUSH); //newest value
|
356 |
sonar_dc.DrawCircle(wxPoint(d_x,d_y), 2);
|
357 |
if (isFront) // @todo for some reason isFront = (!isFront) is not working |
358 |
{ |
359 |
isFront = FALSE; |
360 |
} |
361 |
else
|
362 |
{ |
363 |
isFront = TRUE; |
364 |
} |
365 |
} |
366 |
|
367 |
// Convert from pixels to mm and return
|
368 |
return (unsigned int) ((1000 / PIX_PER_METER) * d); |
369 |
} |
370 |
|
371 |
// x and y is current position of the sonar
|
372 |
void Scout::update_sonar(const wxImage& walls_image, int x, int y, |
373 |
double robot_theta,wxMemoryDC& sonar_dc)
|
374 |
{ |
375 |
// Only rotate the sonar at the correct rate.
|
376 |
if (ros::Time::now() - last_sonar_time < sonar_tick_time)
|
377 |
{ |
378 |
return;
|
379 |
} |
380 |
last_sonar_time = ros::Time::now(); |
381 |
|
382 |
unsigned int d_front = trace_sonar(walls_image, x, y, robot_theta, |
383 |
sonar_position, sonar_dc); |
384 |
unsigned int d_back = trace_sonar(walls_image, x, y, robot_theta, |
385 |
sonar_position + 24, sonar_dc);
|
386 |
|
387 |
// Publish
|
388 |
::messages::sonar_distance msg; |
389 |
msg.pos = sonar_position; |
390 |
msg.distance0 = d_front; |
391 |
msg.distance1 = d_back; |
392 |
msg.stamp = ros::Time::now(); |
393 |
|
394 |
sonar_pub.publish(msg); |
395 |
|
396 |
// Update the sonar rotation
|
397 |
if (sonar_position + sonar_direction <= sonar_stop_r &&
|
398 |
sonar_position + sonar_direction >= sonar_stop_l) |
399 |
{ |
400 |
sonar_position = sonar_position + sonar_direction; |
401 |
} |
402 |
else
|
403 |
{ |
404 |
sonar_direction = -sonar_direction; |
405 |
} |
406 |
} |
407 |
|
408 |
void Scout::update_linesensor(const wxImage& lines_image, int x, int y, |
409 |
double robot_theta)
|
410 |
{ |
411 |
linesensor_readings.clear(); |
412 |
|
413 |
double spacing = scout_image.GetWidth() / (NUM_LINESENSORS - 1); |
414 |
for (int s = 0; s < NUM_LINESENSORS; s++) |
415 |
{ |
416 |
double offset = -(scout_image.GetWidth() / 2) + s * spacing; |
417 |
|
418 |
int sensor_x = (int) (x - LNSNSR_D * cos(robot_theta) - |
419 |
offset * sin(robot_theta)); |
420 |
int sensor_y = (int) (y + LNSNSR_D * sin(robot_theta) - |
421 |
offset * cos(robot_theta)); |
422 |
|
423 |
unsigned char r = lines_image.GetRed(sensor_x, sensor_y); |
424 |
unsigned char g = lines_image.GetGreen(sensor_x, sensor_y); |
425 |
unsigned char b = lines_image.GetBlue(sensor_x, sensor_y); |
426 |
|
427 |
unsigned int reading = rgb_to_grey(r, g, b); |
428 |
|
429 |
linesensor_readings.push_back(reading); |
430 |
} |
431 |
} |
432 |
|
433 |
void Scout::pub_BOM(bool bom_0) { |
434 |
BOM b; |
435 |
|
436 |
b.bom_0 = true;
|
437 |
bom_pub.publish(b); |
438 |
} |
439 |
|
440 |
|
441 |
/// Sends back the position of this scout so scoutsim can save
|
442 |
/// the world state
|
443 |
/// @todo remove dt param
|
444 |
geometry_msgs::Pose2D Scout::update(double dt, wxMemoryDC& path_dc,
|
445 |
wxMemoryDC& sonar_dc, |
446 |
const wxImage& path_image,
|
447 |
const wxImage& lines_image,
|
448 |
const wxImage& walls_image,
|
449 |
wxColour background_color, |
450 |
wxColour sonar_color, |
451 |
world_state state) |
452 |
{ |
453 |
// Assume that the two motors on the same side will be set to
|
454 |
// roughly the same speed. Does not account for slip conditions
|
455 |
// when they are set to different speeds.
|
456 |
float l_speed = (float (motor_fl_speed + motor_bl_speed)) / 2; |
457 |
float r_speed = (float (motor_fr_speed + motor_br_speed)) / 2; |
458 |
|
459 |
// Find linear and angular movement in m
|
460 |
float lin_dist = SIM_TIME_REFRESH_RATE * (l_speed + r_speed) / 2; |
461 |
float ang_dist = SIM_TIME_REFRESH_RATE * (r_speed - l_speed) / SCOUT_WIDTH;
|
462 |
|
463 |
//store currently teleop'd scoutname
|
464 |
//std::stringstream ss;
|
465 |
//ss << "/" << teleop_scoutname;
|
466 |
//current_teleop_scout = ss.str();
|
467 |
|
468 |
Vector2 old_pos = pos; |
469 |
|
470 |
// Update encoders
|
471 |
fl_ticks += (unsigned int) (motor_fl_speed * SIM_TIME_REFRESH_RATE * |
472 |
ENCODER_TICKS_PER_METER); |
473 |
fr_ticks += (unsigned int) (motor_fr_speed * SIM_TIME_REFRESH_RATE * |
474 |
ENCODER_TICKS_PER_METER); |
475 |
bl_ticks += (unsigned int) (motor_bl_speed * SIM_TIME_REFRESH_RATE * |
476 |
ENCODER_TICKS_PER_METER); |
477 |
br_ticks += (unsigned int) (motor_br_speed * SIM_TIME_REFRESH_RATE * |
478 |
ENCODER_TICKS_PER_METER); |
479 |
|
480 |
orient = fmod((float) (orient + ang_dist), (float) (2.0 * PI)); |
481 |
|
482 |
pos.x += cos(orient) * lin_dist; |
483 |
pos.y -= sin(orient) * lin_dist; //Subtract because of the way the simulator handles y directions.
|
484 |
|
485 |
// Clamp to screen size
|
486 |
if (pos.x < 0 || pos.x >= state.canvas_width |
487 |
|| pos.y < 0 || pos.y >= state.canvas_height)
|
488 |
{ |
489 |
ROS_WARN("I hit the wall! (Clamping from [x=%f, y=%f])", pos.x, pos.y);
|
490 |
} |
491 |
|
492 |
pos.x = min(max(pos.x, 0.0f), state.canvas_width); |
493 |
pos.y = min(max(pos.y, 0.0f), state.canvas_height); |
494 |
|
495 |
int canvas_x = pos.x * PIX_PER_METER;
|
496 |
int canvas_y = pos.y * PIX_PER_METER;
|
497 |
|
498 |
|
499 |
{ |
500 |
wxImage rotated_image = |
501 |
scout_image.Rotate(orient - PI/2.0, |
502 |
wxPoint(scout_image.GetWidth() / 2,
|
503 |
scout_image.GetHeight() / 2),
|
504 |
false);
|
505 |
|
506 |
for (int y = 0; y < rotated_image.GetHeight(); ++y) |
507 |
{ |
508 |
for (int x = 0; x < rotated_image.GetWidth(); ++x) |
509 |
{ |
510 |
if (rotated_image.GetRed(x, y) == 255 |
511 |
&& rotated_image.GetBlue(x, y) == 255
|
512 |
&& rotated_image.GetGreen(x, y) == 255)
|
513 |
{ |
514 |
rotated_image.SetAlpha(x, y, 0);
|
515 |
} |
516 |
} |
517 |
} |
518 |
|
519 |
scout = wxBitmap(rotated_image); |
520 |
} |
521 |
|
522 |
Pose p; |
523 |
p.x = pos.x; |
524 |
p.y = pos.y; |
525 |
p.theta = orient; |
526 |
p.linear_velocity = l_speed; |
527 |
p.angular_velocity = r_speed; |
528 |
pose_pub.publish(p); |
529 |
|
530 |
update_linesensor(lines_image, canvas_x, canvas_y, p.theta); |
531 |
if (sonar_on)
|
532 |
{ |
533 |
update_sonar(walls_image, |
534 |
canvas_x + scoutsim::SCOUT_SONAR_X, |
535 |
canvas_y + scoutsim::SCOUT_SONAR_Y, |
536 |
p.theta,sonar_dc); |
537 |
|
538 |
} |
539 |
|
540 |
// Figure out (and publish) the color underneath the scout
|
541 |
{ |
542 |
//wxSize scout_size = wxSize(scout.GetWidth(), scout.GetHeight());
|
543 |
Color color; |
544 |
color.r = path_image.GetRed(canvas_x, canvas_y); |
545 |
color.g = path_image.GetGreen(canvas_x, canvas_y); |
546 |
color.b = path_image.GetBlue(canvas_x, canvas_y); |
547 |
color_pub.publish(color); |
548 |
} |
549 |
|
550 |
ROS_DEBUG("[%s]: pos_x: %f pos_y: %f theta: %f",
|
551 |
node.getNamespace().c_str(), pos.x, pos.y, orient); |
552 |
|
553 |
if (pen_on)
|
554 |
{ |
555 |
if (pos != old_pos)
|
556 |
{ |
557 |
path_dc.SelectObject(*path_bitmap); |
558 |
path_dc.SetPen(pen); |
559 |
path_dc.DrawLine(pos.x * PIX_PER_METER, pos.y * PIX_PER_METER, |
560 |
old_pos.x * PIX_PER_METER, old_pos.y * PIX_PER_METER); |
561 |
} |
562 |
} |
563 |
|
564 |
geometry_msgs::Pose2D my_pose; |
565 |
my_pose.x = pos.x; |
566 |
my_pose.y = pos.y; |
567 |
my_pose.theta = orient; |
568 |
|
569 |
return my_pose;
|
570 |
} |
571 |
|
572 |
void Scout::paint(wxDC& dc)
|
573 |
{ |
574 |
wxSize scout_size = wxSize(scout.GetWidth(), scout.GetHeight()); |
575 |
dc.DrawBitmap(scout, pos.x * PIX_PER_METER - (scout_size.GetWidth() / 2),
|
576 |
pos.y * PIX_PER_METER - (scout_size.GetHeight() / 2), true); |
577 |
} |
578 |
|
579 |
void Scout::set_sonar_visual(bool on) |
580 |
{ |
581 |
sonar_visual_on = on; |
582 |
} |
583 |
} |
584 |
|
585 |
/** @} */
|