scoutos / scout / scoutsim / src / scout.cpp @ 259aaff8
History | View | Annotate | Download (19.2 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 | 43811241 | Alex | , sonar_visual_on(false)
|
67 | 093a1aea | Alex | , sonar_on(true)
|
68 | 60a90290 | Hui Jun Tay | , ignore_behavior(false)
|
69 | 43811241 | Alex | , node (nh) |
70 | 144137a1 | Alex Zirbel | , scout_image(scout_image) |
71 | , pos(pos) |
||
72 | , orient(orient) |
||
73 | 9f547ef7 | Alex Zirbel | , motor_fl_speed(0)
|
74 | , motor_fr_speed(0)
|
||
75 | , motor_bl_speed(0)
|
||
76 | , motor_br_speed(0)
|
||
77 | , fl_ticks(0)
|
||
78 | , fr_ticks(0)
|
||
79 | , bl_ticks(0)
|
||
80 | , br_ticks(0)
|
||
81 | 144137a1 | Alex Zirbel | , pen_on(true)
|
82 | , pen(wxColour(DEFAULT_PEN_R, DEFAULT_PEN_G, DEFAULT_PEN_B)) |
||
83 | 266ae7f2 | Alex Zirbel | { |
84 | 144137a1 | Alex Zirbel | pen.SetWidth(3);
|
85 | scout = wxBitmap(scout_image); |
||
86 | |||
87 | motors_sub = node.subscribe("set_motors", 1, &Scout::setMotors, this); |
||
88 | |||
89 | pose_pub = node.advertise<Pose>("pose", 1); |
||
90 | color_pub = node.advertise<Color>("color_sensor", 1); |
||
91 | 071926c2 | Alex | sonar_pub = node.advertise< ::messages::sonar_distance>("sonar_distance", 1); |
92 | 144137a1 | Alex Zirbel | set_pen_srv = node.advertiseService("set_pen",
|
93 | 266ae7f2 | Alex Zirbel | &Scout::setPenCallback, |
94 | this);
|
||
95 | eb9cff77 | Hui Jun Tay | toggle_sonar_srv = node.advertiseService("sonar_toggle",
|
96 | &Scout::handle_sonar_toggle, |
||
97 | this);
|
||
98 | set_sonar_srv = node.advertiseService("sonar_set_scan",
|
||
99 | &Scout::handle_sonar_set_scan, |
||
100 | this);
|
||
101 | 9f547ef7 | Alex Zirbel | query_encoders_srv = |
102 | node.advertiseService("query_encoders",
|
||
103 | &Scout::query_encoders_callback, |
||
104 | this);
|
||
105 | 266ae7f2 | Alex Zirbel | |
106 | af0d9743 | Alex | query_linesensor_srv = |
107 | node.advertiseService("query_linesensor",
|
||
108 | &Scout::query_linesensor_callback, |
||
109 | this);
|
||
110 | |||
111 | ade1b7f9 | Alex | for (unsigned int i = 0; i < NUM_LINESENSORS; i++) |
112 | { |
||
113 | linesensor_readings.push_back(0);
|
||
114 | } |
||
115 | |||
116 | a2e6bd4c | Alex | // Initialize sonar
|
117 | sonar_position = 0;
|
||
118 | sonar_stop_l = 0;
|
||
119 | sonar_stop_r = 23;
|
||
120 | sonar_direction = 1;
|
||
121 | sonar_tick_time = ros::Duration(scoutsim::SONAR_HALF_SPIN_TIME / 24.0); |
||
122 | f09d002e | Hui Jun Tay | |
123 | // Init latch
|
||
124 | teleop_latch = 0;
|
||
125 | 266ae7f2 | Alex Zirbel | } |
126 | |||
127 | 6257c97d | Alex | float Scout::absolute_to_mps(int absolute_speed) |
128 | { |
||
129 | return ((float) absolute_speed) * MAX_SPEED_MPS / MAX_ABSOLUTE_SPEED; |
||
130 | } |
||
131 | |||
132 | a8480867 | Alex Zirbel | /**
|
133 | * A callback function that sets velocity based on a set_motors
|
||
134 | * request.
|
||
135 | c492be62 | Alex Zirbel | * @todo Use "callback" in all callback function names? Or remove?
|
136 | a8480867 | Alex Zirbel | */
|
137 | 6ebee82c | Alex | void Scout::setMotors(const ::messages::set_motors::ConstPtr& msg) |
138 | a8480867 | Alex Zirbel | { |
139 | 144137a1 | Alex Zirbel | last_command_time = ros::WallTime::now(); |
140 | a8480867 | Alex Zirbel | |
141 | 60a90290 | Hui Jun Tay | //ignore non-teleop commands if commands if teleop is ON
|
142 | f09d002e | Hui Jun Tay | //if (node.getNamespace() != current_teleop_scout || msg->teleop_ON)
|
143 | //{
|
||
144 | |||
145 | //latch value indicates number of uninterrupted teleop messages
|
||
146 | //before teleop latch shifts again
|
||
147 | if (!(msg->teleop_ON) && teleop_latch < 3) |
||
148 | { |
||
149 | teleop_latch++; |
||
150 | } |
||
151 | |||
152 | if (!(msg->teleop_ON) || teleop_latch ==0) |
||
153 | a8480867 | Alex Zirbel | { |
154 | 60a90290 | Hui Jun Tay | if(msg->fl_set)
|
155 | { |
||
156 | motor_fl_speed = absolute_to_mps(msg->fl_speed); |
||
157 | } |
||
158 | if(msg->fr_set)
|
||
159 | { |
||
160 | motor_fr_speed = absolute_to_mps(msg->fr_speed); |
||
161 | } |
||
162 | if(msg->bl_set)
|
||
163 | { |
||
164 | motor_bl_speed = absolute_to_mps(msg->bl_speed); |
||
165 | } |
||
166 | if(msg->br_set)
|
||
167 | { |
||
168 | motor_br_speed = absolute_to_mps(msg->br_speed); |
||
169 | } |
||
170 | f09d002e | Hui Jun Tay | } |
171 | |||
172 | //if a teleop message comes through, decrease the latch
|
||
173 | //latch code works on the assumption there will be more behavior messages
|
||
174 | //than teleop messages
|
||
175 | if (msg->teleop_ON && teleop_latch>0) |
||
176 | { |
||
177 | teleop_latch--; |
||
178 | a8480867 | Alex Zirbel | } |
179 | f09d002e | Hui Jun Tay | //}
|
180 | 60a90290 | Hui Jun Tay | |
181 | 266ae7f2 | Alex Zirbel | } |
182 | eb9cff77 | Hui Jun Tay | |
183 | 071926c2 | Alex | bool Scout::handle_sonar_toggle(::messages::sonar_toggle::Request &req,
|
184 | ::messages::sonar_toggle::Response &res) |
||
185 | eb9cff77 | Hui Jun Tay | { |
186 | if (req.set_on && !sonar_on)
|
||
187 | { |
||
188 | 04114d13 | Alex | ROS_INFO("Turning on the sonar");
|
189 | eb9cff77 | Hui Jun Tay | sonar_on = true;
|
190 | |||
191 | } |
||
192 | else if (!req.set_on && sonar_on) |
||
193 | { |
||
194 | 04114d13 | Alex | ROS_INFO("Turning off the sonar");
|
195 | eb9cff77 | Hui Jun Tay | sonar_on = false;
|
196 | } |
||
197 | else
|
||
198 | { |
||
199 | 04114d13 | Alex | ROS_INFO("Sonar state remains unchanged");
|
200 | eb9cff77 | Hui Jun Tay | } |
201 | 04114d13 | Alex | res.ack = true;
|
202 | return true; |
||
203 | eb9cff77 | Hui Jun Tay | } |
204 | |||
205 | 071926c2 | Alex | bool Scout::handle_sonar_set_scan(::messages::sonar_set_scan::Request &req,
|
206 | ::messages::sonar_set_scan::Response &res) |
||
207 | eb9cff77 | Hui Jun Tay | { |
208 | 04114d13 | Alex | // Code to set the sonar to scan from
|
209 | // req.stop_l to req.stop_r
|
||
210 | if (req.stop_l>=0 and req.stop_r<=23 and req.stop_l<=req.stop_r) |
||
211 | { |
||
212 | ROS_INFO("Setting sonar scan range to [%i, %i]",
|
||
213 | req.stop_l, |
||
214 | req.stop_r); |
||
215 | sonar_stop_l = req.stop_l; |
||
216 | sonar_stop_r = req.stop_r; |
||
217 | sonar_position = req.stop_l; |
||
218 | sonar_direction = 1;
|
||
219 | res.ack = true;
|
||
220 | } |
||
221 | else
|
||
222 | { |
||
223 | ROS_INFO("Bad Input: Input should be integers 0-23, stop_l<stop_r");
|
||
224 | } |
||
225 | return true; |
||
226 | eb9cff77 | Hui Jun Tay | } |
227 | 266ae7f2 | Alex Zirbel | |
228 | bool Scout::setPenCallback(scoutsim::SetPen::Request& req,
|
||
229 | scoutsim::SetPen::Response&) |
||
230 | { |
||
231 | 144137a1 | Alex Zirbel | pen_on = !req.off; |
232 | 266ae7f2 | Alex Zirbel | if (req.off)
|
233 | { |
||
234 | return true; |
||
235 | } |
||
236 | |||
237 | wxPen pen(wxColour(req.r, req.g, req.b)); |
||
238 | if (req.width != 0) |
||
239 | { |
||
240 | pen.SetWidth(req.width); |
||
241 | } |
||
242 | |||
243 | 144137a1 | Alex Zirbel | pen = pen; |
244 | 266ae7f2 | Alex Zirbel | return true; |
245 | } |
||
246 | |||
247 | 6ebee82c | Alex | bool Scout::query_encoders_callback(::messages::query_encoders::Request&,
|
248 | ::messages::query_encoders::Response& res) |
||
249 | 9f547ef7 | Alex Zirbel | { |
250 | res.fl_distance = fl_ticks; |
||
251 | res.fr_distance = fr_ticks; |
||
252 | res.bl_distance = bl_ticks; |
||
253 | res.br_distance = br_ticks; |
||
254 | |||
255 | return true; |
||
256 | } |
||
257 | |||
258 | 6ebee82c | Alex | bool Scout::query_linesensor_callback(::messages::query_linesensor::Request&,
|
259 | ::messages::query_linesensor::Response& res) |
||
260 | af0d9743 | Alex | { |
261 | ade1b7f9 | Alex | res.readings = linesensor_readings; |
262 | |||
263 | return true; |
||
264 | } |
||
265 | af0d9743 | Alex | |
266 | ade1b7f9 | Alex | // Scale to linesensor value
|
267 | a2e6bd4c | Alex | unsigned int Scout::rgb_to_grey(unsigned char r, |
268 | unsigned char g, |
||
269 | unsigned char b) |
||
270 | ade1b7f9 | Alex | { |
271 | // Should be 0 to 255
|
||
272 | unsigned int grey = ((unsigned int) r + (unsigned int) g + (unsigned int) b) / 3; |
||
273 | |||
274 | /// @todo Convert to the proper range
|
||
275 | return 255 - grey; |
||
276 | } |
||
277 | |||
278 | a2e6bd4c | Alex | unsigned int Scout::trace_sonar(const wxImage& walls_image, int x, int y, |
279 | 96ec9388 | Hui Jun Tay | double robot_theta, int sonar_pos, |
280 | wxMemoryDC& sonar_dc) |
||
281 | a2e6bd4c | Alex | { |
282 | 71e1154d | Alex | double angle = robot_theta + (PI * ((float) sonar_pos) / 24.0) - PI / 2; |
283 | a2e6bd4c | Alex | unsigned int d = 0; |
284 | |||
285 | unsigned int reading = 0; |
||
286 | 96ec9388 | Hui Jun Tay | |
287 | c63c9752 | Alex | int d_x = 0; |
288 | int d_y = 0; |
||
289 | |||
290 | a2e6bd4c | Alex | do
|
291 | { |
||
292 | 6639ce9c | viki | d_x = x + (int) floor(d * cos(angle));
|
293 | eb9cff77 | Hui Jun Tay | d_y = y - (int) floor(d * sin(angle));
|
294 | a2e6bd4c | Alex | |
295 | // Out of image boundary
|
||
296 | if (d_x < 0 || d_x >= walls_image.GetWidth() || |
||
297 | d_y < 0 || d_y >= walls_image.GetHeight())
|
||
298 | { |
||
299 | dd065971 | Alex | break;
|
300 | a2e6bd4c | Alex | } |
301 | |||
302 | // Max range
|
||
303 | dd065971 | Alex | if (d > scoutsim::SONAR_MAX_RANGE_PIX)
|
304 | a2e6bd4c | Alex | { |
305 | dd065971 | Alex | break;
|
306 | a2e6bd4c | Alex | } |
307 | |||
308 | // Get the sonar reading at the current position of the sonar
|
||
309 | unsigned char r = walls_image.GetRed(d_x, d_y); |
||
310 | unsigned char g = walls_image.GetGreen(d_x, d_y); |
||
311 | unsigned char b = walls_image.GetBlue(d_x, d_y); |
||
312 | 04114d13 | Alex | |
313 | a2e6bd4c | Alex | reading = rgb_to_grey(r, g, b); |
314 | 04114d13 | Alex | |
315 | a2e6bd4c | Alex | d++; |
316 | } |
||
317 | 71e1154d | Alex | /// @todo Consider using different cutoffs for different features
|
318 | while (reading < 128); /// @todo Get rid of hardcoded stuff like this |
||
319 | 6639ce9c | viki | |
320 | 04114d13 | Alex | if (sonar_visual_on)
|
321 | { |
||
322 | if (isFront)
|
||
323 | { |
||
324 | // draw a circle at the wall_x, wall_y where reading > 128
|
||
325 | sonar_dc.SelectObject(*path_bitmap); |
||
326 | sonar_dc.SetBrush(*wxRED_BRUSH); //old value
|
||
327 | 9cb9623b | Alex | sonar_dc.DrawCircle(wxPoint(old_front_dx, old_front_dy), 2);
|
328 | 04114d13 | Alex | old_front_dx = d_x; |
329 | old_front_dy = d_y; |
||
330 | } |
||
331 | else
|
||
332 | { |
||
333 | // draw a circle at the wall_x, wall_y where reading > 128
|
||
334 | sonar_dc.SelectObject(*path_bitmap); |
||
335 | sonar_dc.SetBrush(*wxRED_BRUSH); //old value
|
||
336 | sonar_dc.DrawCircle(wxPoint(old_back_dx,old_back_dy), 2);
|
||
337 | old_back_dx = d_x; |
||
338 | old_back_dy = d_y; |
||
339 | } |
||
340 | |||
341 | sonar_dc.SetBrush(*wxGREEN_BRUSH); //newest value
|
||
342 | 43811241 | Alex | sonar_dc.DrawCircle(wxPoint(d_x,d_y), 2);
|
343 | if (isFront) // @todo for some reason isFront = (!isFront) is not working |
||
344 | 04114d13 | Alex | { |
345 | isFront = FALSE; |
||
346 | } |
||
347 | else
|
||
348 | { |
||
349 | isFront = TRUE; |
||
350 | } |
||
351 | } |
||
352 | |||
353 | e5ac3afb | Alex | // Convert from pixels to mm and return
|
354 | dd065971 | Alex | return (unsigned int) ((1000 / PIX_PER_METER) * d); |
355 | a2e6bd4c | Alex | } |
356 | |||
357 | 71e1154d | Alex | // x and y is current position of the sonar
|
358 | a2e6bd4c | Alex | void Scout::update_sonar(const wxImage& walls_image, int x, int y, |
359 | eb9cff77 | Hui Jun Tay | double robot_theta,wxMemoryDC& sonar_dc)
|
360 | a2e6bd4c | Alex | { |
361 | // Only rotate the sonar at the correct rate.
|
||
362 | if (ros::Time::now() - last_sonar_time < sonar_tick_time)
|
||
363 | { |
||
364 | return;
|
||
365 | } |
||
366 | last_sonar_time = ros::Time::now(); |
||
367 | |||
368 | unsigned int d_front = trace_sonar(walls_image, x, y, robot_theta, |
||
369 | 43811241 | Alex | sonar_position, sonar_dc); |
370 | a2e6bd4c | Alex | unsigned int d_back = trace_sonar(walls_image, x, y, robot_theta, |
371 | 43811241 | Alex | sonar_position + 24, sonar_dc);
|
372 | a2e6bd4c | Alex | |
373 | // Publish
|
||
374 | 071926c2 | Alex | ::messages::sonar_distance msg; |
375 | a2e6bd4c | Alex | msg.pos = sonar_position; |
376 | msg.distance0 = d_front; |
||
377 | msg.distance1 = d_back; |
||
378 | c06735bb | Hui Jun Tay | msg.stamp = ros::Time::now(); |
379 | a2e6bd4c | Alex | |
380 | sonar_pub.publish(msg); |
||
381 | |||
382 | // Update the sonar rotation
|
||
383 | if (sonar_position + sonar_direction <= sonar_stop_r &&
|
||
384 | sonar_position + sonar_direction >= sonar_stop_l) |
||
385 | { |
||
386 | sonar_position = sonar_position + sonar_direction; |
||
387 | } |
||
388 | else
|
||
389 | { |
||
390 | sonar_direction = -sonar_direction; |
||
391 | } |
||
392 | } |
||
393 | |||
394 | void Scout::update_linesensor(const wxImage& lines_image, int x, int y, |
||
395 | double robot_theta)
|
||
396 | ade1b7f9 | Alex | { |
397 | linesensor_readings.clear(); |
||
398 | |||
399 | double spacing = scout_image.GetWidth() / (NUM_LINESENSORS - 1); |
||
400 | for (int s = 0; s < NUM_LINESENSORS; s++) |
||
401 | af0d9743 | Alex | { |
402 | ade1b7f9 | Alex | double offset = -(scout_image.GetWidth() / 2) + s * spacing; |
403 | af0d9743 | Alex | |
404 | a2e6bd4c | Alex | int sensor_x = (int) (x - LNSNSR_D * cos(robot_theta) - |
405 | offset * sin(robot_theta)); |
||
406 | int sensor_y = (int) (y + LNSNSR_D * sin(robot_theta) - |
||
407 | offset * cos(robot_theta)); |
||
408 | af0d9743 | Alex | |
409 | ade1b7f9 | Alex | unsigned char r = lines_image.GetRed(sensor_x, sensor_y); |
410 | unsigned char g = lines_image.GetGreen(sensor_x, sensor_y); |
||
411 | unsigned char b = lines_image.GetBlue(sensor_x, sensor_y); |
||
412 | |||
413 | a2e6bd4c | Alex |