root / scout / scoutsim / src / sim_frame.cpp @ 1d1281cc
History | View | Annotate | Download (10.7 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 "sim_frame.h" |
| 49 |
|
| 50 |
#include <stdio.h> |
| 51 |
|
| 52 |
#include <ros/package.h> |
| 53 |
#include <cstdlib> |
| 54 |
#include <ctime> |
| 55 |
|
| 56 |
using namespace std; |
| 57 |
|
| 58 |
namespace scoutsim
|
| 59 |
{
|
| 60 |
SimFrame::SimFrame(wxWindow* parent, string map_name)
|
| 61 |
: wxFrame(parent, wxID_ANY, wxT("ScoutSim"), wxDefaultPosition,
|
| 62 |
wxSize(500, 500), wxDEFAULT_FRAME_STYLE & ~wxRESIZE_BORDER) |
| 63 |
, frame_count(0)
|
| 64 |
, id_counter(0)
|
| 65 |
{
|
| 66 |
std::cout << "Constructing sim frame." << std::endl;
|
| 67 |
|
| 68 |
srand(time(NULL));
|
| 69 |
|
| 70 |
update_timer = new wxTimer(this); |
| 71 |
update_timer->Start(16);
|
| 72 |
|
| 73 |
Connect(update_timer->GetId(), wxEVT_TIMER, |
| 74 |
wxTimerEventHandler(SimFrame::onUpdate), NULL, this); |
| 75 |
Connect(wxEVT_PAINT, wxPaintEventHandler(SimFrame::onPaint), |
| 76 |
NULL, this); |
| 77 |
|
| 78 |
std::string scouts[SCOUTSIM_NUM_SCOUTS] =
|
| 79 |
{
|
| 80 |
"scout.png"
|
| 81 |
}; |
| 82 |
|
| 83 |
std::string images_path = ros::package::getPath("scoutsim")+"/images/"; |
| 84 |
for (size_t i = 0; i < SCOUTSIM_NUM_SCOUTS; ++i) |
| 85 |
{
|
| 86 |
scout_images[i].LoadFile( |
| 87 |
wxString::FromAscii((images_path + scouts[i]).c_str())); |
| 88 |
scout_images[i].SetMask(true);
|
| 89 |
scout_images[i].SetMaskColour(255, 255, 255); |
| 90 |
} |
| 91 |
|
| 92 |
/// @todo This should change.
|
| 93 |
meter = scout_images[0].GetHeight();
|
| 94 |
|
| 95 |
map_base_name = ros::package::getPath("scoutsim") + "/maps/" + |
| 96 |
map_name + ".bmp";
|
| 97 |
map_lines_name = ros::package::getPath("scoutsim") + "/maps/" + |
| 98 |
map_name + "_lines.bmp";
|
| 99 |
display_map_name = map_base_name; |
| 100 |
|
| 101 |
wxBitmap lines_bitmap; |
| 102 |
lines_bitmap.LoadFile(wxString::FromAscii(map_lines_name.c_str())); |
| 103 |
lines_image = lines_bitmap.ConvertToImage(); |
| 104 |
|
| 105 |
clear(); |
| 106 |
|
| 107 |
clear_srv = nh.advertiseService("clear",
|
| 108 |
&SimFrame::clearCallback, this);
|
| 109 |
reset_srv = nh.advertiseService("reset",
|
| 110 |
&SimFrame::resetCallback, this);
|
| 111 |
spawn_srv = nh.advertiseService("spawn",
|
| 112 |
&SimFrame::spawnCallback, this);
|
| 113 |
kill_srv = nh.advertiseService("kill",
|
| 114 |
&SimFrame::killCallback, this);
|
| 115 |
|
| 116 |
// Subscribe and publisher wirless from robots
|
| 117 |
wireless_receive = nh.advertise< ::messages::WirelessPacket>("/wireless/receive", 1000); |
| 118 |
wireless_send = nh.subscribe("/wireless/send", 1000, &SimFrame::wirelessCallback, this); |
| 119 |
|
| 120 |
ROS_INFO("Starting scoutsim with node name %s",
|
| 121 |
ros::this_node::getName().c_str()) ; |
| 122 |
|
| 123 |
wxMenu *menuFile = new wxMenu;
|
| 124 |
menuFile->Append(ID_ABOUT, _("&About"));
|
| 125 |
menuFile->AppendSeparator(); |
| 126 |
menuFile->Append(ID_QUIT, _("E&xit"));
|
| 127 |
|
| 128 |
wxMenu *menuSim = new wxMenu;
|
| 129 |
menuSim->Append(ID_CLEAR, _("&Clear"));
|
| 130 |
|
| 131 |
wxMenu *menuView = new wxMenu;
|
| 132 |
menuView->Append(ID_MAP, _("&Map"));
|
| 133 |
menuView->Append(ID_LINES, _("&Lines"));
|
| 134 |
|
| 135 |
wxMenuBar *menuBar = new wxMenuBar;
|
| 136 |
menuBar->Append(menuFile, _("&File"));
|
| 137 |
menuBar->Append(menuSim, _("&Sim"));
|
| 138 |
menuBar->Append(menuView, _("&View"));
|
| 139 |
|
| 140 |
SetMenuBar(menuBar); |
| 141 |
|
| 142 |
width_in_meters = GetSize().GetWidth() / meter; |
| 143 |
height_in_meters = GetSize().GetHeight() / meter; |
| 144 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
| 145 |
} |
| 146 |
|
| 147 |
SimFrame::~SimFrame() |
| 148 |
{
|
| 149 |
delete update_timer;
|
| 150 |
} |
| 151 |
|
| 152 |
bool SimFrame::spawnCallback(scoutsim::Spawn::Request &req,
|
| 153 |
scoutsim::Spawn::Response &res) |
| 154 |
{
|
| 155 |
std::string name = spawnScout(req.name, req.x, req.y, req.theta);
|
| 156 |
if (name.empty())
|
| 157 |
{
|
| 158 |
ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
|
| 159 |
return false; |
| 160 |
} |
| 161 |
|
| 162 |
res.name = name; |
| 163 |
|
| 164 |
return true; |
| 165 |
} |
| 166 |
|
| 167 |
bool SimFrame::killCallback(scoutsim::Kill::Request& req,
|
| 168 |
scoutsim::Kill::Response&) |
| 169 |
{
|
| 170 |
M_Scout::iterator it = scouts.find(req.name); |
| 171 |
if (it == scouts.end())
|
| 172 |
{
|
| 173 |
ROS_ERROR("Tried to kill scout [%s], which does not exist",
|
| 174 |
req.name.c_str()); |
| 175 |
return false; |
| 176 |
} |
| 177 |
|
| 178 |
scouts.erase(it); |
| 179 |
|
| 180 |
return true; |
| 181 |
} |
| 182 |
|
| 183 |
bool SimFrame::hasScout(const std::string& name) |
| 184 |
{
|
| 185 |
return scouts.find(name) != scouts.end();
|
| 186 |
} |
| 187 |
|
| 188 |
std::string SimFrame::spawnScout(const std::string& name, |
| 189 |
float x, float y, float angle) |
| 190 |
{
|
| 191 |
std::string real_name = name;
|
| 192 |
if (real_name.empty())
|
| 193 |
{
|
| 194 |
do
|
| 195 |
{
|
| 196 |
std::stringstream ss; |
| 197 |
ss << "scout" << ++id_counter;
|
| 198 |
real_name = ss.str(); |
| 199 |
} while (hasScout(real_name));
|
| 200 |
} |
| 201 |
else
|
| 202 |
{
|
| 203 |
if (hasScout(real_name))
|
| 204 |
{
|
| 205 |
return ""; |
| 206 |
} |
| 207 |
} |
| 208 |
|
| 209 |
ScoutPtr t(new Scout(ros::NodeHandle(real_name),
|
| 210 |
scout_images[rand() % SCOUTSIM_NUM_SCOUTS], |
| 211 |
Vector2(x, y), angle)); |
| 212 |
scouts[real_name] = t; |
| 213 |
|
| 214 |
ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
|
| 215 |
real_name.c_str(), x, y, angle); |
| 216 |
|
| 217 |
return real_name;
|
| 218 |
} |
| 219 |
|
| 220 |
void SimFrame::onQuit(wxCommandEvent& WXUNUSED(event))
|
| 221 |
{
|
| 222 |
Close(true);
|
| 223 |
} |
| 224 |
|
| 225 |
void SimFrame::onAbout(wxCommandEvent& WXUNUSED(event))
|
| 226 |
{
|
| 227 |
wxMessageBox(_("Scoutsim is the simulator the Colony Project's scout robot.\n"
|
| 228 |
"\nThe Colony Project is a part of the Carnegie Mellon\n"
|
| 229 |
"Robotics Club. Our goal is to use cooperative low-cost\n"
|
| 230 |
"robots to solve challenging problems."),
|
| 231 |
_("About Scoutsim"),
|
| 232 |
wxOK | wxICON_INFORMATION, this );
|
| 233 |
} |
| 234 |
|
| 235 |
void SimFrame::onClear(wxCommandEvent& WXUNUSED(event))
|
| 236 |
{
|
| 237 |
clear(); |
| 238 |
} |
| 239 |
|
| 240 |
void SimFrame::showMap(wxCommandEvent& WXUNUSED(event))
|
| 241 |
{
|
| 242 |
display_map_name = map_base_name; |
| 243 |
clear(); |
| 244 |
} |
| 245 |
|
| 246 |
void SimFrame::showLines(wxCommandEvent& WXUNUSED(event))
|
| 247 |
{
|
| 248 |
display_map_name = map_lines_name; |
| 249 |
clear(); |
| 250 |
} |
| 251 |
|
| 252 |
void SimFrame::clear()
|
| 253 |
{
|
| 254 |
path_dc.SetBackground(wxBrush(wxColour(100, 100, 100))); |
| 255 |
path_dc.Clear(); |
| 256 |
|
| 257 |
path_bitmap.LoadFile(wxString::FromAscii(display_map_name.c_str())); |
| 258 |
path_dc.SelectObject(path_bitmap); |
| 259 |
SetSize(wxSize(path_bitmap.GetWidth(), path_bitmap.GetHeight())); |
| 260 |
} |
| 261 |
|
| 262 |
void SimFrame::onUpdate(wxTimerEvent& evt)
|
| 263 |
{
|
| 264 |
ros::spinOnce(); |
| 265 |
|
| 266 |
updateScouts(); |
| 267 |
|
| 268 |
if (!ros::ok())
|
| 269 |
{
|
| 270 |
Close(); |
| 271 |
} |
| 272 |
} |
| 273 |
|
| 274 |
void SimFrame::onPaint(wxPaintEvent& evt)
|
| 275 |
{
|
| 276 |
wxPaintDC dc(this);
|
| 277 |
|
| 278 |
dc.DrawBitmap(path_bitmap, 0, 0, true); |
| 279 |
|
| 280 |
M_Scout::iterator it = scouts.begin(); |
| 281 |
M_Scout::iterator end = scouts.end(); |
| 282 |
for (; it != end; ++it)
|
| 283 |
{
|
| 284 |
it->second->paint(dc); |
| 285 |
} |
| 286 |
} |
| 287 |
|
| 288 |
void SimFrame::updateScouts()
|
| 289 |
{
|
| 290 |
if (last_scout_update.isZero())
|
| 291 |
{
|
| 292 |
last_scout_update = ros::WallTime::now(); |
| 293 |
return;
|
| 294 |
} |
| 295 |
|
| 296 |
if (frame_count % 3 == 0) |
| 297 |
{
|
| 298 |
path_image = path_bitmap.ConvertToImage(); |
| 299 |
Refresh(); |
| 300 |
} |
| 301 |
|
| 302 |
M_Scout::iterator it = scouts.begin(); |
| 303 |
M_Scout::iterator end = scouts.end(); |
| 304 |
|
| 305 |
world_state state; |
| 306 |
state.canvas_width = width_in_meters; |
| 307 |
state.canvas_height = height_in_meters; |
| 308 |
|
| 309 |
for (; it != end; ++it)
|
| 310 |
{
|
| 311 |
it->second->update(0.016, path_dc, path_image, lines_image, |
| 312 |
path_dc.GetBackground().GetColour(), |
| 313 |
state); |
| 314 |
} |
| 315 |
|
| 316 |
frame_count++; |
| 317 |
} |
| 318 |
|
| 319 |
bool SimFrame::clearCallback(std_srvs::Empty::Request&,
|
| 320 |
std_srvs::Empty::Response&) |
| 321 |
{
|
| 322 |
ROS_INFO("Clearing scoutsim.");
|
| 323 |
clear(); |
| 324 |
return true; |
| 325 |
} |
| 326 |
|
| 327 |
bool SimFrame::resetCallback(std_srvs::Empty::Request&,
|
| 328 |
std_srvs::Empty::Response&) |
| 329 |
{
|
| 330 |
ROS_INFO("Resetting scoutsim.");
|
| 331 |
scouts.clear(); |
| 332 |
id_counter = 0;
|
| 333 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
| 334 |
clear(); |
| 335 |
return true; |
| 336 |
} |
| 337 |
|
| 338 |
void SimFrame::wirelessCallback(const ::messages::WirelessPacket::ConstPtr& msg) |
| 339 |
{
|
| 340 |
wireless_receive.publish(msg); |
| 341 |
} |
| 342 |
} |