Project

General

Profile

Statistics
| Branch: | Revision:

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

History | View | Annotate | Download (2 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
 * @file sim_frame.h
8
 * @author Colony Project, CMU Robotics Club
9
 * @author Alex Zirbel
10
 */
11

    
12
#include <wx/wx.h>
13
#include <wx/event.h>
14
#include <wx/timer.h>
15

    
16
#include <ros/ros.h>
17

    
18
#include <std_srvs/Empty.h>
19
#include <scoutsim/Spawn.h>
20
#include <scoutsim/Kill.h>
21
#include <map>
22

    
23
#include "scout.h"
24

    
25
#define SCOUTSIM_NUM_SCOUTS 1
26

    
27
namespace scoutsim
28
{
29
    class SimFrame : public wxFrame
30
    {
31
        public:
32
            SimFrame(wxWindow* parent);
33
            ~SimFrame();
34

    
35
            std::string spawnScout(const std::string& name,
36
                    float x, float y, float angle);
37

    
38
        private:
39
            void onUpdate(wxTimerEvent& evt);
40
            void onPaint(wxPaintEvent& evt);
41

    
42
            void updateScouts();
43
            void clear();
44
            bool hasScout(const std::string& name);
45

    
46
            bool clearCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
47
            bool resetCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
48
            bool spawnCallback(scoutsim::Spawn::Request&, scoutsim::Spawn::Response&);
49
            bool killCallback(scoutsim::Kill::Request&, scoutsim::Kill::Response&);
50

    
51
            ros::NodeHandle nh_;
52
            wxTimer* update_timer_;
53
            wxBitmap path_bitmap_;
54
            wxImage path_image_;
55
            wxMemoryDC path_dc_;
56

    
57
            uint64_t frame_count_;
58

    
59
            ros::WallTime last_scout_update_;
60

    
61
            ros::ServiceServer clear_srv_;
62
            ros::ServiceServer reset_srv_;
63
            ros::ServiceServer spawn_srv_;
64
            ros::ServiceServer kill_srv_;
65

    
66
            typedef std::map<std::string, ScoutPtr> M_Scout;
67
            M_Scout scouts_;
68
            uint32_t id_counter_;
69

    
70
            wxImage scout_images_[SCOUTSIM_NUM_SCOUTS];
71

    
72
            float meter_;
73
            float width_in_meters_;
74
            float height_in_meters_;
75
    };
76

    
77
}