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