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