scoutos / scout / scoutsim / src / scout.cpp @ 71e1154d
History | View | Annotate | Download (13.9 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 |
float orient)
|
64 |
: node (nh) |
65 |
, scout_image(scout_image) |
66 |
, pos(pos) |
67 |
, orient(orient) |
68 |
, motor_fl_speed(0)
|
69 |
, motor_fr_speed(0)
|
70 |
, motor_bl_speed(0)
|
71 |
, motor_br_speed(0)
|
72 |
, fl_ticks(0)
|
73 |
, fr_ticks(0)
|
74 |
, bl_ticks(0)
|
75 |
, br_ticks(0)
|
76 |
, pen_on(true)
|
77 |
, pen(wxColour(DEFAULT_PEN_R, DEFAULT_PEN_G, DEFAULT_PEN_B)) |
78 |
{ |
79 |
pen.SetWidth(3);
|
80 |
scout = wxBitmap(scout_image); |
81 |
|
82 |
motors_sub = node.subscribe("set_motors", 1, &Scout::setMotors, this); |
83 |
|
84 |
pose_pub = node.advertise<Pose>("pose", 1); |
85 |
color_pub = node.advertise<Color>("color_sensor", 1); |
86 |
sonar_pub = node.advertise<sonar::sonar_distance>("sonar_distance", 1); |
87 |
set_pen_srv = node.advertiseService("set_pen",
|
88 |
&Scout::setPenCallback, |
89 |
this);
|
90 |
query_encoders_srv = |
91 |
node.advertiseService("query_encoders",
|
92 |
&Scout::query_encoders_callback, |
93 |
this);
|
94 |
|
95 |
query_linesensor_srv = |
96 |
node.advertiseService("query_linesensor",
|
97 |
&Scout::query_linesensor_callback, |
98 |
this);
|
99 |
|
100 |
for (unsigned int i = 0; i < NUM_LINESENSORS; i++) |
101 |
{ |
102 |
linesensor_readings.push_back(0);
|
103 |
} |
104 |
|
105 |
meter = scout.GetHeight(); |
106 |
|
107 |
// Initialize sonar
|
108 |
sonar_position = 0;
|
109 |
sonar_stop_l = 0;
|
110 |
sonar_stop_r = 23;
|
111 |
sonar_direction = 1;
|
112 |
sonar_tick_time = ros::Duration(scoutsim::SONAR_HALF_SPIN_TIME / 24.0); |
113 |
} |
114 |
|
115 |
/**
|
116 |
* A callback function that sets velocity based on a set_motors
|
117 |
* request.
|
118 |
* @todo Use "callback" in all callback function names? Or remove?
|
119 |
*/
|
120 |
void Scout::setMotors(const motors::set_motors::ConstPtr& msg) |
121 |
{ |
122 |
last_command_time = ros::WallTime::now(); |
123 |
|
124 |
if(msg->fl_set)
|
125 |
{ |
126 |
motor_fl_speed = msg->fl_speed; |
127 |
} |
128 |
if(msg->fr_set)
|
129 |
{ |
130 |
motor_fr_speed = msg->fr_speed; |
131 |
} |
132 |
if(msg->bl_set)
|
133 |
{ |
134 |
motor_bl_speed = msg->bl_speed; |
135 |
} |
136 |
if(msg->br_set)
|
137 |
{ |
138 |
motor_br_speed = msg->br_speed; |
139 |
} |
140 |
|
141 |
} |
142 |
|
143 |
bool Scout::setPenCallback(scoutsim::SetPen::Request& req,
|
144 |
scoutsim::SetPen::Response&) |
145 |
{ |
146 |
pen_on = !req.off; |
147 |
if (req.off)
|
148 |
{ |
149 |
return true; |
150 |
} |
151 |
|
152 |
wxPen pen(wxColour(req.r, req.g, req.b)); |
153 |
if (req.width != 0) |
154 |
{ |
155 |
pen.SetWidth(req.width); |
156 |
} |
157 |
|
158 |
pen = pen; |
159 |
return true; |
160 |
} |
161 |
|
162 |
bool Scout::query_encoders_callback(encoders::query_encoders::Request&,
|
163 |
encoders::query_encoders::Response& res) |
164 |
{ |
165 |
res.fl_distance = fl_ticks; |
166 |
res.fr_distance = fr_ticks; |
167 |
res.bl_distance = bl_ticks; |
168 |
res.br_distance = br_ticks; |
169 |
|
170 |
return true; |
171 |
} |
172 |
|
173 |
bool Scout::query_linesensor_callback(linesensor::query_linesensor::Request&,
|
174 |
linesensor::query_linesensor::Response& res) |
175 |
{ |
176 |
res.readings = linesensor_readings; |
177 |
|
178 |
return true; |
179 |
} |
180 |
|
181 |
// Scale to linesensor value
|
182 |
unsigned int Scout::rgb_to_grey(unsigned char r, |
183 |
unsigned char g, |
184 |
unsigned char b) |
185 |
{ |
186 |
// Should be 0 to 255
|
187 |
unsigned int grey = ((unsigned int) r + (unsigned int) g + (unsigned int) b) / 3; |
188 |
|
189 |
/// @todo Convert to the proper range
|
190 |
return 255 - grey; |
191 |
} |
192 |
|
193 |
unsigned int Scout::trace_sonar(const wxImage& walls_image, int x, int y, |
194 |
double robot_theta, int sonar_pos) |
195 |
{ |
196 |
double angle = robot_theta + (PI * ((float) sonar_pos) / 24.0) - PI / 2; |
197 |
unsigned int d = 0; |
198 |
|
199 |
unsigned int reading = 0; |
200 |
do
|
201 |
{ |
202 |
int d_x = x + (int) floor(d * cos(angle)); |
203 |
int d_y = y + (int) floor(d * sin(angle)); |
204 |
|
205 |
// Out of image boundary
|
206 |
if (d_x < 0 || d_x >= walls_image.GetWidth() || |
207 |
d_y < 0 || d_y >= walls_image.GetHeight())
|
208 |
{ |
209 |
return d;
|
210 |
} |
211 |
|
212 |
// Max range
|
213 |
if (d > scoutsim::SONAR_MAX_RANGE)
|
214 |
{ |
215 |
return d;
|
216 |
} |
217 |
|
218 |
// Get the sonar reading at the current position of the sonar
|
219 |
unsigned char r = walls_image.GetRed(d_x, d_y); |
220 |
unsigned char g = walls_image.GetGreen(d_x, d_y); |
221 |
unsigned char b = walls_image.GetBlue(d_x, d_y); |
222 |
|
223 |
reading = rgb_to_grey(r, g, b); |
224 |
|
225 |
d++; |
226 |
} |
227 |
/// @todo Consider using different cutoffs for different features
|
228 |
while (reading < 128); /// @todo Get rid of hardcoded stuff like this |
229 |
|
230 |
return d;
|
231 |
} |
232 |
|
233 |
// x and y is current position of the sonar
|
234 |
void Scout::update_sonar(const wxImage& walls_image, int x, int y, |
235 |
double robot_theta)
|
236 |
{ |
237 |
// Only rotate the sonar at the correct rate.
|
238 |
if (ros::Time::now() - last_sonar_time < sonar_tick_time)
|
239 |
{ |
240 |
return;
|
241 |
} |
242 |
last_sonar_time = ros::Time::now(); |
243 |
|
244 |
unsigned int d_front = trace_sonar(walls_image, x, y, robot_theta, |
245 |
sonar_position); |
246 |
unsigned int d_back = trace_sonar(walls_image, x, y, robot_theta, |
247 |
sonar_position + 24);
|
248 |
|
249 |
// Publish
|
250 |
sonar::sonar_distance msg; |
251 |
msg.pos = sonar_position; |
252 |
msg.distance0 = d_front; |
253 |
msg.distance1 = d_back; |
254 |
|
255 |
sonar_pub.publish(msg); |
256 |
|
257 |
// Update the sonar rotation
|
258 |
if (sonar_position + sonar_direction <= sonar_stop_r &&
|
259 |
sonar_position + sonar_direction >= sonar_stop_l) |
260 |
{ |
261 |
sonar_position = sonar_position + sonar_direction; |
262 |
} |
263 |
else
|
264 |
{ |
265 |
sonar_direction = -sonar_direction; |
266 |
} |
267 |
} |
268 |
|
269 |
void Scout::update_linesensor(const wxImage& lines_image, int x, int y, |
270 |
double robot_theta)
|
271 |
{ |
272 |
linesensor_readings.clear(); |
273 |
|
274 |
double spacing = scout_image.GetWidth() / (NUM_LINESENSORS - 1); |
275 |
for (int s = 0; s < NUM_LINESENSORS; s++) |
276 |
{ |
277 |
double offset = -(scout_image.GetWidth() / 2) + s * spacing; |
278 |
|
279 |
int sensor_x = (int) (x - LNSNSR_D * cos(robot_theta) - |
280 |
offset * sin(robot_theta)); |
281 |
int sensor_y = (int) (y + LNSNSR_D * sin(robot_theta) - |
282 |
offset * cos(robot_theta)); |
283 |
|
284 |
unsigned char r = lines_image.GetRed(sensor_x, sensor_y); |
285 |
unsigned char g = lines_image.GetGreen(sensor_x, sensor_y); |
286 |
unsigned char b = lines_image.GetBlue(sensor_x, sensor_y); |
287 |
|
288 |
unsigned int reading = rgb_to_grey(r, g, b); |
289 |
|
290 |
linesensor_readings.push_back(reading); |
291 |
} |
292 |
} |
293 |
|
294 |
/// Sends back the position of this scout so scoutsim can save
|
295 |
/// the world state
|
296 |
geometry_msgs::Pose2D Scout::update(double dt, wxMemoryDC& path_dc,
|
297 |
const wxImage& path_image,
|
298 |
const wxImage& lines_image,
|
299 |
const wxImage& walls_image,
|
300 |
wxColour background_color, |
301 |
world_state state) |
302 |
{ |
303 |
// Assume that the two motors on the same side will be set to
|
304 |
// roughly the same speed. Does not account for slip conditions
|
305 |
// when they are set to different speeds.
|
306 |
float l_speed = (float (motor_fl_speed + motor_bl_speed)) / 2; |
307 |
float r_speed = (float (motor_fr_speed + motor_br_speed)) / 2; |
308 |
|
309 |
// Set the linear and angular speeds
|
310 |
float lin_vel = SPEED_SCALE_FACTOR * (l_speed + r_speed) / 2; |
311 |
float ang_vel = SPEED_SCALE_FACTOR * (r_speed - l_speed);
|
312 |
|
313 |
Vector2 old_pos = pos; |
314 |
|
315 |
// Update encoders
|
316 |
/// @todo replace
|
317 |
fl_ticks += (unsigned int) motor_fl_speed; |
318 |
fr_ticks += (unsigned int) motor_fr_speed; |
319 |
bl_ticks += (unsigned int) motor_bl_speed; |
320 |
br_ticks += (unsigned int) motor_br_speed; |
321 |
|
322 |
orient = fmod(orient + ang_vel * dt, 2*PI);
|
323 |
pos.x += sin(orient + PI/2.0) * lin_vel * dt; |
324 |
pos.y += cos(orient + PI/2.0) * lin_vel * dt; |
325 |
|
326 |
// Clamp to screen size
|
327 |
if (pos.x < 0 || pos.x >= state.canvas_width |
328 |
|| pos.y < 0 || pos.y >= state.canvas_height)
|
329 |
{ |
330 |
ROS_WARN("Oh no! I hit the wall! (Clamping from [x=%f, y=%f])", pos.x, pos.y);
|
331 |
} |
332 |
|
333 |
pos.x = min(max(pos.x, 0.0f), state.canvas_width); |
334 |
pos.y = min(max(pos.y, 0.0f), state.canvas_height); |
335 |
|
336 |
int canvas_x = pos.x * meter;
|
337 |
int canvas_y = pos.y * meter;
|
338 |
|
339 |
{ |
340 |
wxImage rotated_image = |
341 |
scout_image.Rotate(orient - PI/2.0, |
342 |
wxPoint(scout_image.GetWidth() / 2,
|
343 |
scout_image.GetHeight() / 2),
|
344 |
false);
|
345 |
|
346 |
for (int y = 0; y < rotated_image.GetHeight(); ++y) |
347 |
{ |
348 |
for (int x = 0; x < rotated_image.GetWidth(); ++x) |
349 |
{ |
350 |
if (rotated_image.GetRed(x, y) == 255 |
351 |
&& rotated_image.GetBlue(x, y) == 255
|
352 |
&& rotated_image.GetGreen(x, y) == 255)
|
353 |
{ |
354 |
rotated_image.SetAlpha(x, y, 0);
|
355 |
} |
356 |
} |
357 |
} |
358 |
|
359 |
scout = wxBitmap(rotated_image); |
360 |
} |
361 |
|
362 |
Pose p; |
363 |
p.x = pos.x; |
364 |
p.y = state.canvas_height - pos.y; |
365 |
p.theta = orient; |
366 |
p.linear_velocity = lin_vel; |
367 |
p.angular_velocity = ang_vel; |
368 |
pose_pub.publish(p); |
369 |
|
370 |
update_linesensor(lines_image, canvas_x, canvas_y, p.theta); |
371 |
update_sonar(walls_image, |
372 |
canvas_x + scoutsim::SCOUT_SONAR_X, |
373 |
canvas_y + scoutsim::SCOUT_SONAR_Y, |
374 |
p.theta); |
375 |
|
376 |
// Figure out (and publish) the color underneath the scout
|
377 |
{ |
378 |
//wxSize scout_size = wxSize(scout.GetWidth(), scout.GetHeight());
|
379 |
Color color; |
380 |
color.r = path_image.GetRed(canvas_x, canvas_y); |
381 |
color.g = path_image.GetGreen(canvas_x, canvas_y); |
382 |
color.b = path_image.GetBlue(canvas_x, canvas_y); |
383 |
color_pub.publish(color); |
384 |
} |
385 |
|
386 |
ROS_DEBUG("[%s]: pos_x: %f pos_y: %f theta: %f",
|
387 |
node.getNamespace().c_str(), pos.x, pos.y, orient); |
388 |
|
389 |
if (pen_on)
|
390 |
{ |
391 |
if (pos != old_pos)
|
392 |
{ |
393 |
path_dc.SetPen(pen); |
394 |
path_dc.DrawLine(pos.x * meter, pos.y * meter, |
395 |
old_pos.x * meter, old_pos.y * meter); |
396 |
} |
397 |
} |
398 |
|
399 |
geometry_msgs::Pose2D my_pose; |
400 |
my_pose.x = pos.x; |
401 |
my_pose.y = pos.y; |
402 |
my_pose.theta = orient; |
403 |
|
404 |
return my_pose;
|
405 |
} |
406 |
|
407 |
void Scout::paint(wxDC& dc)
|
408 |
{ |
409 |
wxSize scout_size = wxSize(scout.GetWidth(), scout.GetHeight()); |
410 |
dc.DrawBitmap(scout, pos.x * meter - (scout_size.GetWidth() / 2),
|
411 |
pos.y * meter - (scout_size.GetHeight() / 2), true); |
412 |
} |
413 |
|
414 |
} |