scoutos / scout / scoutsim / src / scout.cpp @ 98ed4757
History | View | Annotate | Download (19.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 | 3a73516c | Alex | /**
|
49 | * @file scout.cpp
|
||
50 | *
|
||
51 | * @ingroup scoutsim
|
||
52 | * @{
|
||
53 | */
|
||
54 | |||
55 | a8480867 | Alex Zirbel | #include "scout.h" |
56 | 266ae7f2 | Alex Zirbel | |
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 | af0d9743 | Alex | using namespace std; |
64 | |||
65 | 266ae7f2 | Alex Zirbel | namespace scoutsim
|
66 | { |
||
67 | 3a73516c | Alex | /**
|
68 | * The scout object, which is responsible for refreshing itself and
|
||
69 | * updating its position and simulated sensors.
|
||
70 | *
|
||
71 | * @ingroup scoutsim
|
||
72 | */
|
||
73 | 266ae7f2 | Alex Zirbel | Scout::Scout(const ros::NodeHandle& nh,
|
74 | 9f547ef7 | Alex Zirbel | const wxImage& scout_image,
|
75 | const Vector2& pos,
|
||
76 | 6639ce9c | viki | wxBitmap *path_bitmap, |
77 | 9f547ef7 | Alex Zirbel | float orient)
|
78 | 6639ce9c | viki | : path_bitmap(path_bitmap) |
79 | 43811241 | Alex | , sonar_visual_on(false)
|
80 | 093a1aea | Alex | , sonar_on(true)
|
81 | 60a90290 | Hui Jun Tay | , ignore_behavior(false)
|
82 | 43811241 | Alex | , node (nh) |
83 | 144137a1 | Alex Zirbel | , scout_image(scout_image) |
84 | , pos(pos) |
||
85 | , orient(orient) |
||
86 | 9f547ef7 | Alex Zirbel | , 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 | 144137a1 | Alex Zirbel | , pen_on(true)
|
95 | , pen(wxColour(DEFAULT_PEN_R, DEFAULT_PEN_G, DEFAULT_PEN_B)) |
||
96 | 266ae7f2 | Alex Zirbel | { |
97 | 144137a1 | Alex Zirbel | 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 | 071926c2 | Alex | sonar_pub = node.advertise< ::messages::sonar_distance>("sonar_distance", 1); |
105 | 98ed4757 | Hui Jun Tay | bom_pub = node.advertise<BOM>("BOM", 1); |
106 | 144137a1 | Alex Zirbel | set_pen_srv = node.advertiseService("set_pen",
|
107 | 266ae7f2 | Alex Zirbel | &Scout::setPenCallback, |
108 | this);
|
||
109 | eb9cff77 | Hui Jun Tay | 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 | 9f547ef7 | Alex Zirbel | query_encoders_srv = |
116 | node.advertiseService("query_encoders",
|
||
117 | &Scout::query_encoders_callback, |
||
118 | this);
|
||
119 | 266ae7f2 | Alex Zirbel | |
120 | af0d9743 | Alex | query_linesensor_srv = |
121 | node.advertiseService("query_linesensor",
|
||
122 | &Scout::query_linesensor_callback, |
||
123 | this);
|
||
124 | |||
125 | ade1b7f9 | Alex | for (unsigned int i = 0; i < NUM_LINESENSORS; i++) |
126 | { |
||
127 | linesensor_readings.push_back(0);
|
||
128 | } |
||
129 | |||
130 | a2e6bd4c | Alex | // 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 | f09d002e | Hui Jun Tay | |
137 | // Init latch
|
||
138 | teleop_latch = 0;
|
||
139 | 266ae7f2 | Alex Zirbel | } |
140 | |||
141 | 6257c97d | Alex | float Scout::absolute_to_mps(int absolute_speed) |
142 | { |
||
143 | return ((float) absolute_speed) * MAX_SPEED_MPS / MAX_ABSOLUTE_SPEED; |
||
144 | } |
||
145 | |||
146 | a8480867 | Alex Zirbel | /**
|
147 | * A callback function that sets velocity based on a set_motors
|
||
148 | * request.
|
||
149 | c492be62 | Alex Zirbel | * @todo Use "callback" in all callback function names? Or remove?
|
150 | a8480867 | Alex Zirbel | */
|
151 | 6ebee82c | Alex | void Scout::setMotors(const ::messages::set_motors::ConstPtr& msg) |
152 | a8480867 | Alex Zirbel | { |
153 | 144137a1 | Alex Zirbel | last_command_time = ros::WallTime::now(); |
154 | a8480867 | Alex Zirbel | |
155 | 60a90290 | Hui Jun Tay | //ignore non-teleop commands if commands if teleop is ON
|
156 | f09d002e | Hui Jun Tay | //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 | a8480867 | Alex Zirbel | { |
168 | 60a90290 | Hui Jun Tay | 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 | f09d002e | Hui Jun Tay | } |
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 | a8480867 | Alex Zirbel | } |
193 | f09d002e | Hui Jun Tay | //}
|
194 | 60a90290 | Hui Jun Tay | |
195 | 266ae7f2 | Alex Zirbel | } |
196 | eb9cff77 | Hui Jun Tay | |
197 | 071926c2 | Alex | bool Scout::handle_sonar_toggle(::messages::sonar_toggle::Request &req,
|
198 | ::messages::sonar_toggle::Response &res) |
||
199 | eb9cff77 | Hui Jun Tay | { |
200 | if (req.set_on && !sonar_on)
|
||
201 | { |
||
202 | 04114d13 | Alex | ROS_INFO("Turning on the sonar");
|
203 | eb9cff77 | Hui Jun Tay | sonar_on = true;
|
204 | |||
205 | } |
||
206 | else if (!req.set_on && sonar_on) |
||
207 | { |
||
208 | 04114d13 | Alex | ROS_INFO("Turning off the sonar");
|
209 | eb9cff77 | Hui Jun Tay | sonar_on = false;
|
210 | } |
||
211 | else
|
||
212 | { |
||
213 | 04114d13 | Alex | ROS_INFO("Sonar state remains unchanged");
|
214 | eb9cff77 | Hui Jun Tay | } |
215 | 04114d13 | Alex | res.ack = true;
|
216 | return true; |
||
217 | eb9cff77 | Hui Jun Tay | } |
218 | |||
219 | 071926c2 | Alex | bool Scout::handle_sonar_set_scan(::messages::sonar_set_scan::Request &req,
|
220 | ::messages::sonar_set_scan::Response &res) |
||
221 | eb9cff77 | Hui Jun Tay | { |
222 | 04114d13 | Alex | // 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 | eb9cff77 | Hui Jun Tay | } |
241 | 266ae7f2 | Alex Zirbel | |
242 | bool Scout::setPenCallback(scoutsim::SetPen::Request& req,
|
||
243 | scoutsim::SetPen::Response&) |
||
244 | { |
||
245 | 144137a1 | Alex Zirbel | pen_on = !req.off; |
246 | 266ae7f2 | Alex Zirbel | 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 | 144137a1 | Alex Zirbel | pen = pen; |
258 | 266ae7f2 | Alex Zirbel | return true; |
259 | } |
||
260 | |||
261 | 6ebee82c | Alex | bool Scout::query_encoders_callback(::messages::query_encoders::Request&,
|
262 | ::messages::query_encoders::Response& res) |
||
263 | 9f547ef7 | Alex Zirbel | { |
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 | 6ebee82c | Alex | bool Scout::query_linesensor_callback(::messages::query_linesensor::Request&,
|
273 | ::messages::query_linesensor::Response& res) |
||
274 | af0d9743 | Alex | { |
275 | ade1b7f9 | Alex | res.readings = linesensor_readings; |
276 | |||
277 | return true; |
||
278 | } |
||
279 | af0d9743 | Alex | |
280 | ade1b7f9 | Alex | // Scale to linesensor value
|
281 | a2e6bd4c | Alex | unsigned int Scout::rgb_to_grey(unsigned char r, |
282 | unsigned char g, |
||
283 | unsigned char b) |
||
284 | ade1b7f9 | Alex | { |
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 | a2e6bd4c | Alex | unsigned int Scout::trace_sonar(const wxImage& walls_image, int x, int y, |
293 | 96ec9388 | Hui Jun Tay | double robot_theta, int sonar_pos, |
294 | wxMemoryDC& sonar_dc) |
||
295 | a2e6bd4c | Alex | { |
296 | 71e1154d | Alex | double angle = robot_theta + (PI * ((float) sonar_pos) / 24.0) - PI / 2; |
297 | a2e6bd4c | Alex | unsigned int d = 0; |
298 | |||
299 | unsigned int reading = 0; |
||
300 | 96ec9388 | Hui Jun Tay | |
301 | c63c9752 | Alex | int d_x = 0; |
302 | int d_y = 0; |
||
303 | |||
304 | a2e6bd4c | Alex | do
|
305 | { |
||
306 | 6639ce9c | viki | d_x = x + (int) floor(d * cos(angle));
|
307 | eb9cff77 | Hui Jun Tay | d_y = y - (int) floor(d * sin(angle));
|
308 | a2e6bd4c | Alex | |
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 | dd065971 | Alex | break;
|
314 | a2e6bd4c | Alex | } |
315 | |||
316 | // Max range
|
||
317 | dd065971 | Alex | if (d > scoutsim::SONAR_MAX_RANGE_PIX)
|
318 | a2e6bd4c | Alex | { |
319 | dd065971 | Alex | break;
|
320 | a2e6bd4c | Alex | } |
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 | 04114d13 | Alex | |
327 | a2e6bd4c | Alex | reading = rgb_to_grey(r, g, b); |
328 | 04114d13 | Alex | |
329 | a2e6bd4c | Alex | d++; |
330 | } |
||
331 | 71e1154d | Alex | /// @todo Consider using different cutoffs for different features
|
332 | while (reading < 128); /// @todo Get rid of hardcoded stuff like this |
||
333 | 6639ce9c | viki | |
334 | 04114d13 | Alex | 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 | 9cb9623b | Alex | sonar_dc.DrawCircle(wxPoint(old_front_dx, old_front_dy), 2);
|
342 | 04114d13 | Alex | 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 | 43811241 | Alex | sonar_dc.DrawCircle(wxPoint(d_x,d_y), 2);
|
357 | if (isFront) // @todo for some reason isFront = (!isFront) is not working |
||
358 | 04114d13 | Alex | { |
359 | isFront = FALSE; |
||
360 | } |
||
361 | else
|
||
362 | { |
||
363 | isFront = TRUE; |
||
364 | } |
||
365 | } |
||
366 | |||
367 | e5ac3afb | Alex | // Convert from pixels to mm and return
|
368 | dd065971 | Alex | return (unsigned int) ((1000 / PIX_PER_METER) * d); |
369 | a2e6bd4c | Alex | } |
370 | |||
371 | 71e1154d | Alex | // x and y is current position of the sonar
|
372 | a2e6bd4c | Alex | void Scout::update_sonar(const wxImage& walls_image, int x, int y, |
373 | eb9cff77 | Hui Jun Tay | double robot_theta,wxMemoryDC& sonar_dc)
|
374 | a2e6bd4c | Alex | { |
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 | 43811241 | Alex | sonar_position, sonar_dc); |
384 | a2e6bd4c | Alex | unsigned int d_back = trace_sonar(walls_image, x, y, robot_theta, |
385 | 43811241 | Alex | sonar_position + 24, sonar_dc);
|
386 | a2e6bd4c | Alex | |
387 | // Publish
|
||
388 | 071926c2 | Alex | ::messages::sonar_distance msg; |
389 | a2e6bd4c | Alex | msg.pos = sonar_position; |
390 | msg.distance0 = d_front; |
||
391 | msg.distance1 = d_back; |
||
392 | c06735bb | Hui Jun Tay | msg.stamp = ros::Time::now(); |
393 | a2e6bd4c | Alex | |
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 | ade1b7f9 | Alex | { |
411 | linesensor_readings.clear(); |
||
412 | |||
413 | double spacing = scout_image.GetWidth() / (NUM_LINESENSORS - 1); |
||
414 | for (int s = 0; s < NUM_LINESENSORS; s++) |
||
415 | af0d9743 | Alex | { |
416 | ade1b7f9 | Alex | double offset = -(scout_image.GetWidth() / 2) + s * spacing; |
417 | af0d9743 | Alex | |
418 | a2e6bd4c | Alex | 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 | af0d9743 | Alex | |
423 | ade1b7f9 | Alex | 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 | a2e6bd4c | Alex | unsigned int reading = rgb_to_grey(r, g, b); |
428 | ade1b7f9 | Alex | |
429 | linesensor_readings.push_back(reading); |
||
430 | } |
||
431 | af0d9743 | Alex | } |
432 | |||
433 | 98ed4757 | Hui Jun Tay | 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 | 9b3564f3 | Alex Zirbel | /// Sends back the position of this scout so scoutsim can save
|
442 | /// the world state
|
||
443 | 7db6cf9f | Priya | /// @todo remove dt param
|
444 | 9b3564f3 | Alex Zirbel | geometry_msgs::Pose2D Scout::update(double dt, wxMemoryDC& path_dc,
|
445 | 04114d13 | Alex | wxMemoryDC& sonar_dc, |
446 | 9b3564f3 | Alex Zirbel | const wxImage& path_image,
|
447 | ade1b7f9 | Alex | const wxImage& lines_image,
|
448 | a2e6bd4c | Alex | const wxImage& walls_image,
|
449 | 9b3564f3 | Alex Zirbel | wxColour background_color, |
450 | c63c9752 | Alex | wxColour sonar_color, |
451 | f09d002e | Hui Jun Tay | world_state state) |
452 | 266ae7f2 | Alex Zirbel | { |
453 | 9f547ef7 | Alex Zirbel | // 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 | c63c9752 | Alex | // Find linear and angular movement in m
|
460 | 7f095440 | Priya | float lin_dist = SIM_TIME_REFRESH_RATE * (l_speed + r_speed) / 2; |
461 | fa857318 | Priya | float ang_dist = SIM_TIME_REFRESH_RATE * (r_speed - l_speed) / SCOUT_WIDTH;
|
462 | 9f547ef7 | Alex Zirbel | |
463 | 60a90290 | Hui Jun Tay | //store currently teleop'd scoutname
|
464 | f09d002e | Hui Jun Tay | //std::stringstream ss;
|
465 | //ss << "/" << teleop_scoutname;
|
||
466 | //current_teleop_scout = ss.str();
|
||
467 | 60a90290 | Hui Jun Tay | |
468 | 144137a1 | Alex Zirbel | Vector2 old_pos = pos; |
469 | 266ae7f2 | Alex Zirbel | |
470 | 9f547ef7 | Alex Zirbel | // Update encoders
|
471 | 7f095440 | Priya | fl_ticks += (unsigned int) (motor_fl_speed * SIM_TIME_REFRESH_RATE * |
472 | c63c9752 | Alex | ENCODER_TICKS_PER_METER); |
473 | 7f095440 | Priya | fr_ticks += (unsigned int) (motor_fr_speed * SIM_TIME_REFRESH_RATE * |
474 | c63c9752 | Alex | ENCODER_TICKS_PER_METER); |
475 | 7f095440 | Priya | bl_ticks += (unsigned int) (motor_bl_speed * SIM_TIME_REFRESH_RATE * |
476 | c63c9752 | Alex | ENCODER_TICKS_PER_METER); |
477 | 7f095440 | Priya | br_ticks += (unsigned int) (motor_br_speed * SIM_TIME_REFRESH_RATE * |
478 | c63c9752 | Alex | ENCODER_TICKS_PER_METER); |
479 | |||
480 | orient = fmod((float) (orient + ang_dist), (float) (2.0 * PI)); |
||
481 | 9f547ef7 | Alex Zirbel | |
482 | fa857318 | Priya | pos.x += cos(orient) * lin_dist; |
483 | pos.y -= sin(orient) * lin_dist; //Subtract because of the way the simulator handles y directions.
|
||
484 | 266ae7f2 | Alex Zirbel | |
485 | // Clamp to screen size
|
||
486 | e3f69e61 | Alex | if (pos.x < 0 || pos.x >= state.canvas_width |
487 | || pos.y < 0 || pos.y >= state.canvas_height)
|
||
488 | 266ae7f2 | Alex Zirbel | { |
489 | c63c9752 | Alex | ROS_WARN("I hit the wall! (Clamping from [x=%f, y=%f])", pos.x, pos.y);
|
490 | 266ae7f2 | Alex Zirbel | } |
491 | |||
492 | af0d9743 | Alex | pos.x = min(max(pos.x, 0.0f), state.canvas_width); |
493 | pos.y = min(max(pos.y, 0.0f), state.canvas_height); |
||
494 | 266ae7f2 | Alex Zirbel | |
495 | c63c9752 | Alex | int canvas_x = pos.x * PIX_PER_METER;
|
496 | int canvas_y = pos.y * PIX_PER_METER;
|
||
497 | 266ae7f2 | Alex Zirbel | |
498 | 60a90290 | Hui Jun Tay | |
499 | 266ae7f2 | Alex Zirbel | { |
500 | wxImage rotated_image = |
||
501 | 144137a1 | Alex Zirbel | scout_image.Rotate(orient - PI/2.0, |
502 | wxPoint(scout_image.GetWidth() / 2,
|
||
503 | ade1b7f9 | Alex | scout_image.GetHeight() / 2),
|
504 | 5e2c3dc1 | Alex | false);
|
505 | 266ae7f2 | Alex Zirbel | |
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 | 144137a1 | Alex Zirbel | scout = wxBitmap(rotated_image); |
520 | 266ae7f2 | Alex Zirbel | } |
521 | |||
522 | Pose p; |
||
523 | 144137a1 | Alex Zirbel | p.x = pos.x; |
524 | ddfeb111 | Priya | p.y = pos.y; |
525 | 144137a1 | Alex Zirbel | p.theta = orient; |
526 | c63c9752 | Alex | p.linear_velocity = l_speed; |
527 | p.angular_velocity = r_speed; |
||
528 | 144137a1 | Alex Zirbel | pose_pub.publish(p); |
529 | 266ae7f2 | Alex Zirbel | |
530 | ade1b7f9 | Alex | update_linesensor(lines_image, canvas_x, canvas_y, p.theta); |
531 | eb9cff77 | Hui Jun Tay | 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 | ade1b7f9 | Alex | |
538 | eb9cff77 | Hui Jun Tay | } |
539 | 43811241 | Alex | |
540 | 266ae7f2 | Alex Zirbel | // Figure out (and publish) the color underneath the scout
|
541 | { |
||
542 | 23b8119f | Alex | //wxSize scout_size = wxSize(scout.GetWidth(), scout.GetHeight());
|
543 | 266ae7f2 | Alex Zirbel | 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 | 144137a1 | Alex Zirbel | color_pub.publish(color); |
548 | 266ae7f2 | Alex Zirbel | } |
549 | |||
550 | ROS_DEBUG("[%s]: pos_x: %f pos_y: %f theta: %f",
|
||
551 | 144137a1 | Alex Zirbel | node.getNamespace().c_str(), pos.x, pos.y, orient); |
552 | 266ae7f2 | Alex Zirbel | |
553 | 144137a1 | Alex Zirbel | if (pen_on)
|
554 | 266ae7f2 | Alex Zirbel | { |
555 | 144137a1 | Alex Zirbel | if (pos != old_pos)
|
556 | 266ae7f2 | Alex Zirbel | { |
557 | 6639ce9c | viki | path_dc.SelectObject(*path_bitmap); |
558 | 144137a1 | Alex Zirbel | path_dc.SetPen(pen); |
559 | c63c9752 | Alex | 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 | 266ae7f2 | Alex Zirbel | } |
562 | } |
||
563 | e3f69e61 | Alex | |
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 | 266ae7f2 | Alex Zirbel | } |
571 | |||
572 | void Scout::paint(wxDC& dc)
|
||
573 | { |
||
574 | 144137a1 | Alex Zirbel | wxSize scout_size = wxSize(scout.GetWidth(), scout.GetHeight()); |
575 | c63c9752 | Alex | dc.DrawBitmap(scout, pos.x * PIX_PER_METER - (scout_size.GetWidth() / 2),
|
576 | pos.y * PIX_PER_METER - (scout_size.GetHeight() / 2), true); |
||
577 | 266ae7f2 | Alex Zirbel | } |
578 | 43811241 | Alex | |
579 | void Scout::set_sonar_visual(bool on) |
||
580 | { |
||
581 | sonar_visual_on = on; |
||
582 | } |
||
583 | 266ae7f2 | Alex Zirbel | } |
584 | 3a73516c | Alex | |
585 | /** @} */ |