Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / scoutsim / src / scout.cpp @ af0d9743

History | View | Annotate | Download (9.6 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
        set_pen_srv = node.advertiseService("set_pen",
87
                                            &Scout::setPenCallback,
88
                                            this);
89
        query_encoders_srv =
90
            node.advertiseService("query_encoders",
91
                                  &Scout::query_encoders_callback,
92
                                  this);
93

    
94
        query_linesensor_srv =
95
            node.advertiseService("query_linesensor",
96
                                  &Scout::query_linesensor_callback,
97
                                  this);
98

    
99
        meter = scout.GetHeight();
100
    }
101

    
102
    /**
103
     * A callback function that sets velocity based on a set_motors
104
     * request.
105
     * @todo Use "callback" in all callback function names? Or remove?
106
     */
107
    void Scout::setMotors(const motors::set_motors::ConstPtr& msg)
108
    {
109
        last_command_time = ros::WallTime::now();
110

    
111
        if(msg->fl_set)
112
        {
113
            motor_fl_speed = msg->fl_speed;
114
        }
115
        if(msg->fr_set)
116
        {
117
            motor_fr_speed = msg->fr_speed;
118
        }
119
        if(msg->bl_set)
120
        {
121
            motor_bl_speed = msg->bl_speed;
122
        }
123
        if(msg->br_set)
124
        {
125
            motor_br_speed = msg->br_speed;
126
        }
127

    
128
    }
129

    
130
    float Scout::getSonar(float angle)
131
    {
132

    
133
        return 0.0;
134
    }
135

    
136
    bool Scout::setPenCallback(scoutsim::SetPen::Request& req,
137
                               scoutsim::SetPen::Response&)
138
    {
139
        pen_on = !req.off;
140
        if (req.off)
141
        {
142
            return true;
143
        }
144

    
145
        wxPen pen(wxColour(req.r, req.g, req.b));
146
        if (req.width != 0)
147
        {
148
            pen.SetWidth(req.width);
149
        }
150

    
151
        pen = pen;
152
        return true;
153
    }
154

    
155
    bool Scout::query_encoders_callback(encoders::query_encoders::Request&,
156
                                        encoders::query_encoders::Response& res)
157
    {
158
        res.fl_distance = fl_ticks;
159
        res.fr_distance = fr_ticks;
160
        res.bl_distance = bl_ticks;
161
        res.br_distance = br_ticks;
162

    
163
        return true;
164
    }
165

    
166
    bool Scout::query_linesensor_callback(linesensor::query_linesensor::Request&,
167
                                          linesensor::query_linesensor::Response& res)
168
    {
169
        vector<unsigned int> readings;
170

    
171
        for (unsigned int i = 0; i < 8; i++)
172
        {
173
            readings.push_back(8 - i);
174
        }
175

    
176
        res.readings = readings;
177

    
178
        return true;
179
    }
180

    
181
    /// Sends back the position of this scout so scoutsim can save
182
    /// the world state
183
    geometry_msgs::Pose2D Scout::update(double dt, wxMemoryDC& path_dc,
184
                                        const wxImage& path_image,
185
                                        wxColour background_color,
186
                                        world_state state)
187
    {
188
        // Assume that the two motors on the same side will be set to
189
        // roughly the same speed. Does not account for slip conditions
190
        // when they are set to different speeds.
191
        float l_speed = (float (motor_fl_speed + motor_bl_speed)) / 2;
192
        float r_speed = (float (motor_fr_speed + motor_br_speed)) / 2;
193

    
194
        // Set the linear and angular speeds
195
        float lin_vel = SPEED_SCALE_FACTOR * (l_speed + r_speed) / 2;
196
        float ang_vel = SPEED_SCALE_FACTOR * (r_speed - l_speed);
197

    
198
        Vector2 old_pos = pos;
199

    
200
        // Update encoders
201
        /// @todo replace
202
        fl_ticks += (unsigned int) motor_fl_speed;
203
        fr_ticks += (unsigned int) motor_fr_speed;
204
        bl_ticks += (unsigned int) motor_bl_speed;
205
        br_ticks += (unsigned int) motor_br_speed;
206

    
207
        orient = fmod(orient + ang_vel * dt, 2*PI);
208
        pos.x += sin(orient + PI/2.0) * lin_vel * dt;
209
        pos.y += cos(orient + PI/2.0) * lin_vel * dt;
210

    
211
        // Clamp to screen size
212
        if (pos.x < 0 || pos.x >= state.canvas_width
213
                || pos.y < 0 || pos.y >= state.canvas_height)
214
        {
215
            ROS_WARN("Oh no! I hit the wall! (Clamping from [x=%f, y=%f])", pos.x, pos.y);
216
        }
217

    
218
        pos.x = min(max(pos.x, 0.0f), state.canvas_width);
219
        pos.y = min(max(pos.y, 0.0f), state.canvas_height);
220

    
221
        int canvas_x = pos.x * meter;
222
        int canvas_y = pos.y * meter;
223

    
224
        {
225
            wxImage rotated_image =
226
                scout_image.Rotate(orient - PI/2.0,
227
                                   wxPoint(scout_image.GetWidth() / 2,
228
                                            scout_image.GetHeight() / 2),
229
                                   false);
230

    
231
            for (int y = 0; y < rotated_image.GetHeight(); ++y)
232
            {
233
                for (int x = 0; x < rotated_image.GetWidth(); ++x)
234
                {
235
                    if (rotated_image.GetRed(x, y) == 255
236
                            && rotated_image.GetBlue(x, y) == 255
237
                            && rotated_image.GetGreen(x, y) == 255)
238
                    {
239
                        rotated_image.SetAlpha(x, y, 0);
240
                    }
241
                }
242
            }
243

    
244
            scout = wxBitmap(rotated_image);
245
        }
246

    
247
        Pose p;
248
        p.x = pos.x;
249
        p.y = state.canvas_height - pos.y;
250
        p.theta = orient;
251
        p.linear_velocity = lin_vel;
252
        p.angular_velocity = ang_vel;
253
        pose_pub.publish(p);
254

    
255
        // Figure out (and publish) the color underneath the scout
256
        {
257
            wxSize scout_size = wxSize(scout.GetWidth(), scout.GetHeight());
258
            Color color;
259
            color.r = path_image.GetRed(canvas_x, canvas_y);
260
            color.g = path_image.GetGreen(canvas_x, canvas_y);
261
            color.b = path_image.GetBlue(canvas_x, canvas_y);
262
            color_pub.publish(color);
263
        }
264

    
265
        ROS_DEBUG("[%s]: pos_x: %f pos_y: %f theta: %f",
266
                  node.getNamespace().c_str(), pos.x, pos.y, orient);
267

    
268
        if (pen_on)
269
        {
270
            if (pos != old_pos)
271
            {
272
                path_dc.SetPen(pen);
273
                path_dc.DrawLine(pos.x * meter, pos.y * meter,
274
                                 old_pos.x * meter, old_pos.y * meter);
275
            }
276
        }
277

    
278
        geometry_msgs::Pose2D my_pose;
279
        my_pose.x = pos.x;
280
        my_pose.y = pos.y;
281
        my_pose.theta = orient;
282

    
283
        return my_pose;
284
    }
285

    
286
    void Scout::paint(wxDC& dc)
287
    {
288
        wxSize scout_size = wxSize(scout.GetWidth(), scout.GetHeight());
289
        dc.DrawBitmap(scout, pos.x * meter - (scout_size.GetWidth() / 2),
290
                      pos.y * meter - (scout_size.GetHeight() / 2), true);
291
    }
292

    
293
}