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