scoutos / scout / scoutsim / src / sim_frame.cpp @ 4612f7e4
History | View | Annotate | Download (8.44 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 <ros/package.h> |
51 |
#include <cstdlib> |
52 |
#include <ctime> |
53 |
|
54 |
#define DEFAULT_BG_R 0x45 |
55 |
#define DEFAULT_BG_G 0x56 |
56 |
#define DEFAULT_BG_B 0xff |
57 |
|
58 |
namespace scoutsim
|
59 |
{ |
60 |
|
61 |
SimFrame::SimFrame(wxWindow* parent) |
62 |
: wxFrame(parent, wxID_ANY, wxT("ScoutSim"), wxDefaultPosition,
|
63 |
wxSize(500, 500), wxDEFAULT_FRAME_STYLE & ~wxRESIZE_BORDER) |
64 |
, frame_count(0)
|
65 |
, id_counter(0)
|
66 |
{ |
67 |
srand(time(NULL));
|
68 |
|
69 |
update_timer = new wxTimer(this); |
70 |
update_timer->Start(16);
|
71 |
|
72 |
Connect(update_timer->GetId(), wxEVT_TIMER, |
73 |
wxTimerEventHandler(SimFrame::onUpdate), NULL, this); |
74 |
Connect(wxEVT_PAINT, wxPaintEventHandler(SimFrame::onPaint), |
75 |
NULL, this); |
76 |
|
77 |
nh.setParam("background_r", DEFAULT_BG_R);
|
78 |
nh.setParam("background_g", DEFAULT_BG_G);
|
79 |
nh.setParam("background_b", DEFAULT_BG_B);
|
80 |
|
81 |
std::string scouts[SCOUTSIM_NUM_SCOUTS] =
|
82 |
{ |
83 |
"scout.png"
|
84 |
}; |
85 |
|
86 |
std::string images_path = ros::package::getPath("scoutsim")+"/images/"; |
87 |
for (size_t i = 0; i < SCOUTSIM_NUM_SCOUTS; ++i) |
88 |
{ |
89 |
scout_images[i].LoadFile( |
90 |
wxString::FromAscii((images_path + scouts[i]).c_str())); |
91 |
scout_images[i].SetMask(true);
|
92 |
scout_images[i].SetMaskColour(255, 255, 255); |
93 |
} |
94 |
|
95 |
meter = scout_images[0].GetHeight();
|
96 |
|
97 |
path_bitmap = wxBitmap(GetSize().GetWidth(), GetSize().GetHeight()); |
98 |
path_dc.SelectObject(path_bitmap); |
99 |
clear(); |
100 |
|
101 |
clear_srv = nh.advertiseService("clear",
|
102 |
&SimFrame::clearCallback, this);
|
103 |
reset_srv = nh.advertiseService("reset",
|
104 |
&SimFrame::resetCallback, this);
|
105 |
spawn_srv = nh.advertiseService("spawn",
|
106 |
&SimFrame::spawnCallback, this);
|
107 |
kill_srv = nh.advertiseService("kill",
|
108 |
&SimFrame::killCallback, this);
|
109 |
|
110 |
ROS_INFO("Starting scoutsim with node name %s",
|
111 |
ros::this_node::getName().c_str()) ; |
112 |
|
113 |
width_in_meters = GetSize().GetWidth() / meter; |
114 |
height_in_meters = GetSize().GetHeight() / meter; |
115 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
116 |
} |
117 |
|
118 |
SimFrame::~SimFrame() |
119 |
{ |
120 |
delete update_timer;
|
121 |
} |
122 |
|
123 |
bool SimFrame::spawnCallback(scoutsim::Spawn::Request &req,
|
124 |
scoutsim::Spawn::Response &res) |
125 |
{ |
126 |
std::string name = spawnScout(req.name, req.x, req.y, req.theta);
|
127 |
if (name.empty())
|
128 |
{ |
129 |
ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
|
130 |
return false; |
131 |
} |
132 |
|
133 |
res.name = name; |
134 |
|
135 |
return true; |
136 |
} |
137 |
|
138 |
bool SimFrame::killCallback(scoutsim::Kill::Request& req,
|
139 |
scoutsim::Kill::Response&) |
140 |
{ |
141 |
M_Scout::iterator it = scouts.find(req.name); |
142 |
if (it == scouts.end())
|
143 |
{ |
144 |
ROS_ERROR("Tried to kill scout [%s], which does not exist",
|
145 |
req.name.c_str()); |
146 |
return false; |
147 |
} |
148 |
|
149 |
scouts.erase(it); |
150 |
|
151 |
return true; |
152 |
} |
153 |
|
154 |
bool SimFrame::hasScout(const std::string& name) |
155 |
{ |
156 |
return scouts.find(name) != scouts.end();
|
157 |
} |
158 |
|
159 |
std::string SimFrame::spawnScout(const std::string& name, float x, |
160 |
float y, float angle) |
161 |
{ |
162 |
std::string real_name = name;
|
163 |
if (real_name.empty())
|
164 |
{ |
165 |
do
|
166 |
{ |
167 |
std::stringstream ss; |
168 |
ss << "scout" << ++id_counter;
|
169 |
real_name = ss.str(); |
170 |
} while (hasScout(real_name));
|
171 |
} |
172 |
else
|
173 |
{ |
174 |
if (hasScout(real_name))
|
175 |
{ |
176 |
return ""; |
177 |
} |
178 |
} |
179 |
|
180 |
ScoutPtr t(new Scout(ros::NodeHandle(real_name),
|
181 |
scout_images[rand() % SCOUTSIM_NUM_SCOUTS], |
182 |
Vector2(x, y), angle)); |
183 |
scouts[real_name] = t; |
184 |
|
185 |
ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
|
186 |
real_name.c_str(), x, y, angle); |
187 |
|
188 |
return real_name;
|
189 |
} |
190 |
|
191 |
void SimFrame::clear()
|
192 |
{ |
193 |
int r = DEFAULT_BG_R;
|
194 |
int g = DEFAULT_BG_G;
|
195 |
int b = DEFAULT_BG_B;
|
196 |
|
197 |
nh.param("background_r", r, r);
|
198 |
nh.param("background_g", g, g);
|
199 |
nh.param("background_b", b, b);
|
200 |
|
201 |
path_dc.SetBackground(wxBrush(wxColour(r, g, b))); |
202 |
path_dc.Clear(); |
203 |
} |
204 |
|
205 |
void SimFrame::onUpdate(wxTimerEvent& evt)
|
206 |
{ |
207 |
ros::spinOnce(); |
208 |
|
209 |
updateScouts(); |
210 |
|
211 |
if (!ros::ok())
|
212 |
{ |
213 |
Close(); |
214 |
} |
215 |
} |
216 |
|
217 |
void SimFrame::onPaint(wxPaintEvent& evt)
|
218 |
{ |
219 |
wxPaintDC dc(this);
|
220 |
|
221 |
dc.DrawBitmap(path_bitmap, 0, 0, true); |
222 |
|
223 |
M_Scout::iterator it = scouts.begin(); |
224 |
M_Scout::iterator end = scouts.end(); |
225 |
for (; it != end; ++it)
|
226 |
{ |
227 |
it->second->paint(dc); |
228 |
} |
229 |
} |
230 |
|
231 |
void SimFrame::updateScouts()
|
232 |
{ |
233 |
if (last_scout_update.isZero())
|
234 |
{ |
235 |
last_scout_update = ros::WallTime::now(); |
236 |
return;
|
237 |
} |
238 |
|
239 |
if (frame_count % 3 == 0) |
240 |
{ |
241 |
path_image = path_bitmap.ConvertToImage(); |
242 |
Refresh(); |
243 |
} |
244 |
|
245 |
M_Scout::iterator it = scouts.begin(); |
246 |
M_Scout::iterator end = scouts.end(); |
247 |
for (; it != end; ++it)
|
248 |
{ |
249 |
it->second->update(0.016, path_dc, path_image, |
250 |
path_dc.GetBackground().GetColour(), |
251 |
width_in_meters, height_in_meters); |
252 |
} |
253 |
|
254 |
frame_count++; |
255 |
} |
256 |
|
257 |
bool SimFrame::clearCallback(std_srvs::Empty::Request&,
|
258 |
std_srvs::Empty::Response&) |
259 |
{ |
260 |
ROS_INFO("Clearing scoutsim.");
|
261 |
clear(); |
262 |
return true; |
263 |
} |
264 |
|
265 |
bool SimFrame::resetCallback(std_srvs::Empty::Request&,
|
266 |
std_srvs::Empty::Response&) |
267 |
{ |
268 |
ROS_INFO("Resetting scoutsim.");
|
269 |
scouts.clear(); |
270 |
id_counter = 0;
|
271 |
spawnScout("", width_in_meters / 2.0, height_in_meters / 2.0, 0); |
272 |
clear(); |
273 |
return true; |
274 |
} |
275 |
|
276 |
} |