Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / scoutsim / src / sim_frame.cpp @ a8480867

History | View | Annotate | Download (6.6 KB)

1
/*
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 "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
            "scout.png"
49
        };
50

    
51
        std::string images_path = ros::package::getPath("scoutsim")+"/images/";
52
        for (size_t i = 0; i < SCOUTSIM_NUM_SCOUTS; ++i)
53
        {
54
            scout_images_[i].LoadFile(
55
                wxString::FromAscii((images_path + scouts[i]).c_str()));
56
            scout_images_[i].SetMask(true);
57
            scout_images_[i].SetMaskColour(255, 255, 255);
58
        }
59

    
60
        meter_ = scout_images_[0].GetHeight();
61

    
62
        path_bitmap_ = wxBitmap(GetSize().GetWidth(), GetSize().GetHeight());
63
        path_dc_.SelectObject(path_bitmap_);
64
        clear();
65

    
66
        clear_srv_ = nh_.advertiseService("clear",
67
                                          &SimFrame::clearCallback, this);
68
        reset_srv_ = nh_.advertiseService("reset",
69
                                          &SimFrame::resetCallback, this);
70
        spawn_srv_ = nh_.advertiseService("spawn",
71
                                          &SimFrame::spawnCallback, this);
72
        kill_srv_ = nh_.advertiseService("kill",
73
                                         &SimFrame::killCallback, this);
74

    
75
        ROS_INFO("Starting scoutsim with node name %s",
76
                 ros::this_node::getName().c_str()) ;
77

    
78
        width_in_meters_ = GetSize().GetWidth() / meter_;
79
        height_in_meters_ = GetSize().GetHeight() / meter_;
80
        spawnScout("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0);
81
    }
82

    
83
    SimFrame::~SimFrame()
84
    {
85
        delete update_timer_;
86
    }
87

    
88
    bool SimFrame::spawnCallback(scoutsim::Spawn::Request& req,
89
                                 scoutsim::Spawn::Response& res)
90
    {
91
        std::string name = spawnScout(req.name, req.x, req.y, req.theta);
92
        if (name.empty())
93
        {
94
            ROS_ERROR("A scout named [%s] already exists", req.name.c_str());
95
            return false;
96
        }
97

    
98
        res.name = name;
99

    
100
        return true;
101
    }
102

    
103
    bool SimFrame::killCallback(scoutsim::Kill::Request& req,
104
                                scoutsim::Kill::Response&)
105
    {
106
        M_Scout::iterator it = scouts_.find(req.name);
107
        if (it == scouts_.end())
108
        {
109
            ROS_ERROR("Tried to kill scout [%s], which does not exist",
110
                      req.name.c_str());
111
            return false;
112
        }
113

    
114
        scouts_.erase(it);
115

    
116
        return true;
117
    }
118

    
119
    bool SimFrame::hasScout(const std::string& name)
120
    {
121
        return scouts_.find(name) != scouts_.end();
122
    }
123

    
124
    std::string SimFrame::spawnScout(const std::string& name, float x,
125
                                       float y, float angle)
126
    {
127
        std::string real_name = name;
128
        if (real_name.empty())
129
        {
130
            do
131
            {
132
                std::stringstream ss;
133
                ss << "scout" << ++id_counter_;
134
                real_name = ss.str();
135
            } while (hasScout(real_name));
136
        }
137
        else
138
        {
139
            if (hasScout(real_name))
140
            {
141
                return "";
142
            }
143
        }
144

    
145
        ScoutPtr t(new Scout(ros::NodeHandle(real_name),
146
                   scout_images_[rand() % SCOUTSIM_NUM_SCOUTS],
147
                   Vector2(x, y), angle));
148
        scouts_[real_name] = t;
149

    
150
        ROS_INFO("Spawning scout [%s] at x=[%f], y=[%f], theta=[%f]",
151
                 real_name.c_str(), x, y, angle);
152

    
153
        return real_name;
154
    }
155

    
156
    void SimFrame::clear()
157
    {
158
        int r = DEFAULT_BG_R;
159
        int g = DEFAULT_BG_G;
160
        int b = DEFAULT_BG_B;
161

    
162
        nh_.param("background_r", r, r);
163
        nh_.param("background_g", g, g);
164
        nh_.param("background_b", b, b);
165

    
166
        path_dc_.SetBackground(wxBrush(wxColour(r, g, b)));
167
        path_dc_.Clear();
168
    }
169

    
170
    void SimFrame::onUpdate(wxTimerEvent& evt)
171
    {
172
        ros::spinOnce();
173

    
174
        updateScouts();
175

    
176
        if (!ros::ok())
177
        {
178
            Close();
179
        }
180
    }
181

    
182
    void SimFrame::onPaint(wxPaintEvent& evt)
183
    {
184
        wxPaintDC dc(this);
185

    
186
        dc.DrawBitmap(path_bitmap_, 0, 0, true);
187

    
188
        M_Scout::iterator it = scouts_.begin();
189
        M_Scout::iterator end = scouts_.end();
190
        for (; it != end; ++it)
191
        {
192
            it->second->paint(dc);
193
        }
194
    }
195

    
196
    void SimFrame::updateScouts()
197
    {
198
        if (last_scout_update_.isZero())
199
        {
200
            last_scout_update_ = ros::WallTime::now();
201
            return;
202
        }
203

    
204
        if (frame_count_ % 3 == 0)
205
        {
206
            path_image_ = path_bitmap_.ConvertToImage();
207
            Refresh();
208
        }
209

    
210
        M_Scout::iterator it = scouts_.begin();
211
        M_Scout::iterator end = scouts_.end();
212
        for (; it != end; ++it)
213
        {
214
            it->second->update(0.016, path_dc_, path_image_,
215
                               path_dc_.GetBackground().GetColour(),
216
                               width_in_meters_, height_in_meters_);
217
        }
218

    
219
        ++frame_count_;
220
    }
221

    
222

    
223
    bool SimFrame::clearCallback(std_srvs::Empty::Request&,
224
                                 std_srvs::Empty::Response&)
225
    {
226
        ROS_INFO("Clearing scoutsim.");
227
        clear();
228
        return true;
229
    }
230

    
231
    bool SimFrame::resetCallback(std_srvs::Empty::Request&,
232
                                 std_srvs::Empty::Response&)
233
    {
234
        ROS_INFO("Resetting scoutsim.");
235
        scouts_.clear();
236
        id_counter_ = 0;
237
        spawnScout("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0);
238
        clear();
239
        return true;
240
    }
241

    
242
}