Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / scoutsim / src / scout.cpp @ 6257c97d

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