root / scout / scoutsim / src / sim_frame.cpp @ 266ae7f2
History | View | Annotate | Download (6.73 KB)
1 | 266ae7f2 | Alex Zirbel | /*
|
---|---|---|---|
2 | * This package was developed by the CMU Robotics Club project using code
|
||
3 | * from Willow Garage, Inc. Please see licensing.txt for details.
|
||
4 | *
|
||
5 | * All rights reserved.
|
||
6 | *
|
||
7 | * @brief Keeps track of the frame (visualization of the whole environment).
|
||
8 | * @file sim_frame.cpp
|
||
9 | * @author Colony Project, CMU Robotics Club
|
||
10 | * @author Alex Zirbel
|
||
11 | */
|
||
12 | |||
13 | #include "scoutsim/sim_frame.h" |
||
14 | |||
15 | #include <ros/package.h> |
||
16 | #include <cstdlib> |
||
17 | #include <ctime> |
||
18 | |||
19 | #define DEFAULT_BG_R 0x45 |
||
20 | #define DEFAULT_BG_G 0x56 |
||
21 | #define DEFAULT_BG_B 0xff |
||
22 | |||
23 | namespace scoutsim
|
||
24 | { |
||
25 | |||
26 | SimFrame::SimFrame(wxWindow* parent) |
||
27 | : wxFrame(parent, wxID_ANY, wxT("ScoutSim"), wxDefaultPosition,
|
||
28 | wxSize(500, 500), wxDEFAULT_FRAME_STYLE & ~wxRESIZE_BORDER) |
||
29 | , frame_count_(0)
|
||
30 | , id_counter_(0)
|
||
31 | { |
||
32 | srand(time(NULL));
|
||
33 | |||
34 | update_timer_ = new wxTimer(this); |
||
35 | update_timer_->Start(16);
|
||
36 | |||
37 | Connect(update_timer_->GetId(), wxEVT_TIMER, |
||
38 | wxTimerEventHandler(SimFrame::onUpdate), NULL, this); |
||
39 | Connect(wxEVT_PAINT, wxPaintEventHandler(SimFrame::onPaint), |
||
40 | NULL, this); |
||
41 | |||
42 | nh_.setParam("background_r", DEFAULT_BG_R);
|
||
43 | nh_.setParam("background_g", DEFAULT_BG_G);
|
||
44 | nh_.setParam("background_b", DEFAULT_BG_B);
|
||
45 | |||
46 | std::string scouts[SCOUTSIM_NUM_SCOUTS] =
|
||
47 | { |
||
48 | "box-turtle.png",
|
||
49 | "robot-turtle.png",
|
||
50 | "sea-turtle.png",
|
||
51 | "diamondback.png",
|
||
52 | "electric.png"
|
||
53 | }; |
||
54 | |||
55 | std::string images_path = ros::package::getPath("scoutsim")+"/images/"; |
||
56 | for (size_t i = 0; i < SCOUTSIM_NUM_SCOUTS; ++i) |
||
57 | { |
||
58 | scout_images_[i].LoadFile( |
||
59 | wxString::FromAscii((images_path + scouts[i]).c_str())); |
||
60 | scout_images_[i].SetMask(true);
|
||
61 | scout_images_[i].SetMaskColour(255, 255, 255); |
||
62 | } |
||
63 | |||
64 | meter_ = scout_images_[0].GetHeight();
|
||
65 | |||
66 | path_bitmap_ = wxBitmap(GetSize().GetWidth(), GetSize().GetHeight()); |
||
67 | path_dc_.SelectObject(path_bitmap_); |
||
68 | clear(); |
||
69 | |||
70 | clear_srv_ = nh_.advertiseService("clear",
|
||
71 | &SimFrame::clearCallback, this);
|
||
72 | reset_srv_ = nh_.advertiseService("reset",
|
||
73 | &SimFrame::resetCallback, this);
|
||
74 | spawn_srv_ = nh_.advertiseService("spawn",
|
||
75 | &SimFrame::spawnCallback, this);
|
||
76 | kill_srv_ = nh_.advertiseService("kill",
|
||
77 | &SimFrame::killCallback, this);
|
||
78 | |||
79 | ROS_INFO("Starting scoutsim with node name %s",
|
||
80 | ros::this_node::getName().c_str()) ; |
||
81 | |||
82 | width_in_meters_ = GetSize().GetWidth() / meter_; |
||
83 | height_in_meters_ = GetSize().GetHeight() / meter_; |
||
84 | spawnScout("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0); |
||
85 | } |
||
86 | |||
87 | SimFrame::~SimFrame() |
||
88 | { |
||
89 | delete update_timer_;
|
||
90 | } |
||
91 | |||
92 | bool SimFrame::spawnCallback(scoutsim::Spawn::Request& req,
|
||
93 | scoutsim::Spawn::Response& res) |
||
94 | { |
||
95 | std::string name = spawnScout(req.name, req.x, req.y, req.theta);
|
||
96 | if (name.empty())
|
||
97 | { |
||
98 | ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
|
||
99 | return false; |
||
100 | } |
||
101 | |||
102 | res.name = name; |
||
103 | |||
104 | return true; |
||
105 | } |
||
106 | |||
107 | bool SimFrame::killCallback(scoutsim::Kill::Request& req,
|
||
108 | scoutsim::Kill::Response&) |
||
109 | { |
||
110 | M_Scout::iterator it = scouts_.find(req.name); |
||
111 | if (it == scouts_.end())
|
||
112 | { |
||
113 | ROS_ERROR("Tried to kill scout [%s], which does not exist",
|
||
114 | req.name.c_str()); |
||
115 | return false; |
||
116 | } |
||
117 | |||
118 | scouts_.erase(it); |
||
119 | |||
120 | return true; |
||
121 | } |
||
122 | |||
123 | bool SimFrame::hasScout(const std::string& name) |
||
124 | { |
||
125 | return scouts_.find(name) != scouts_.end();
|
||
126 | } |
||
127 | |||
128 | std::string SimFrame::spawnScout(const std::string& name, float x, |
||
129 | float y, float angle) |
||
130 | { |
||
131 | std::string real_name = name;
|
||
132 | if (real_name.empty())
|
||
133 | { |
||
134 | do
|
||
135 | { |
||
136 | std::stringstream ss; |
||
137 | ss << "scout" << ++id_counter_;
|
||
138 | real_name = ss.str(); |
||
139 | } while (hasScout(real_name));
|
||
140 | } |
||
141 | else
|
||
142 | { |
||
143 | if (hasScout(real_name))
|
||
144 | { |
||
145 | return ""; |
||
146 | } |
||
147 | } |
||
148 | |||
149 | ScoutPtr t(new Scout(ros::NodeHandle(real_name),
|
||
150 | scout_images_[rand() % SCOUTSIM_NUM_SCOUTS], |
||
151 | Vector2(x, y), angle)); |
||
152 | scouts_[real_name] = t; |
||
153 | |||
154 | ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
|
||
155 | real_name.c_str(), x, y, angle); |
||
156 | |||
157 | return real_name;
|
||
158 | } |
||
159 | |||
160 | void SimFrame::clear()
|
||
161 | { |
||
162 | int r = DEFAULT_BG_R;
|
||
163 | int g = DEFAULT_BG_G;
|
||
164 | int b = DEFAULT_BG_B;
|
||
165 | |||
166 | nh_.param("background_r", r, r);
|
||
167 | nh_.param("background_g", g, g);
|
||
168 | nh_.param("background_b", b, b);
|
||
169 | |||
170 | path_dc_.SetBackground(wxBrush(wxColour(r, g, b))); |
||
171 | path_dc_.Clear(); |
||
172 | } |
||
173 | |||
174 | void SimFrame::onUpdate(wxTimerEvent& evt)
|
||
175 | { |
||
176 | ros::spinOnce(); |
||
177 | |||
178 | updateScouts(); |
||
179 | |||
180 | if (!ros::ok())
|
||
181 | { |
||
182 | Close(); |
||
183 | } |
||
184 | } |
||
185 | |||
186 | void SimFrame::onPaint(wxPaintEvent& evt)
|
||
187 | { |
||
188 | wxPaintDC dc(this);
|
||
189 | |||
190 | dc.DrawBitmap(path_bitmap_, 0, 0, true); |
||
191 | |||
192 | M_Scout::iterator it = scouts_.begin(); |
||
193 | M_Scout::iterator end = scouts_.end(); |
||
194 | for (; it != end; ++it)
|
||
195 | { |
||
196 | it->second->paint(dc); |
||
197 | } |
||
198 | } |
||
199 | |||
200 | void SimFrame::updateScouts()
|
||
201 | { |
||
202 | if (last_scout_update_.isZero())
|
||
203 | { |
||
204 | last_scout_update_ = ros::WallTime::now(); |
||
205 | return;
|
||
206 | } |
||
207 | |||
208 | if (frame_count_ % 3 == 0) |
||
209 | { |
||
210 | path_image_ = path_bitmap_.ConvertToImage(); |
||
211 | Refresh(); |
||
212 | } |
||
213 | |||
214 | M_Scout::iterator it = scouts_.begin(); |
||
215 | M_Scout::iterator end = scouts_.end(); |
||
216 | for (; it != end; ++it)
|
||
217 | { |
||
218 | it->second->update(0.016, path_dc_, path_image_, |
||
219 | path_dc_.GetBackground().GetColour(), |
||
220 | width_in_meters_, height_in_meters_); |
||
221 | } |
||
222 | |||
223 | ++frame_count_; |
||
224 | } |
||
225 | |||
226 | |||
227 | bool SimFrame::clearCallback(std_srvs::Empty::Request&,
|
||
228 | std_srvs::Empty::Response&) |
||
229 | { |
||
230 | ROS_INFO("Clearing scoutsim.");
|
||
231 | clear(); |
||
232 | return true; |
||
233 | } |
||
234 | |||
235 | bool SimFrame::resetCallback(std_srvs::Empty::Request&,
|
||
236 | std_srvs::Empty::Response&) |
||
237 | { |
||
238 | ROS_INFO("Resetting scoutsim.");
|
||
239 | scouts_.clear(); |
||
240 | id_counter_ = 0;
|
||
241 | spawnScout("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0); |
||
242 | clear(); |
||
243 | return true; |
||
244 | } |
||
245 | |||
246 | } |