Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / scoutsim / src / emitter.h @ 18800d29

History | View | Annotate | Download (2.51 KB)

1
#ifndef _SCOUTSIM_EMITTER_H_
2
#define _SCOUTSIM_EMITTER_H_
3

    
4
#include <ros/ros.h>
5
#include <vector>
6
#include <boost/shared_ptr.hpp>
7

    
8
#include <scoutsim/Pose.h>
9
#include <scoutsim/SetPen.h>
10
#include <scoutsim/Color.h>
11

    
12
#include <geometry_msgs/Pose2D.h>
13

    
14
#include <wx/wx.h>
15

    
16
#include "scout.h"
17
#include "scoutsim_internal.h"
18
#include "scout_constants.h"
19

    
20
#define PI 3.14159265
21

    
22
#define NUM_LINESENSORS 8
23

    
24
// Distance, pixels, from center of robot to the linesensors.
25
#define LNSNSR_D 20
26

    
27
#define BOM_APERTURE (PI / 3.0)
28
#define BOM_DISTANCE 1.0
29

    
30
namespace scoutsim
31
{
32

    
33
    class Emitter
34
    {
35
        public:
36
            Emitter(const ros::NodeHandle& nh,const wxImage& emitter_image,
37
                  const Vector2& pos, wxBitmap *path_bitmap, float orient,
38
                  float aperture, int distance);
39

    
40
            geometry_msgs::Pose2D update(double dt, wxMemoryDC& path_dc,
41
                                         const wxImage& path_image,
42
                                         const wxImage& lines_image,
43
                                         const wxImage& walls_image,
44
                                         wxColour background_color,
45
                                         world_state state);
46

    
47
            geometry_msgs::Pose2D get_pos();
48
            void paint(wxDC& dc);
49
            void set_emitter_visual(bool on);
50

    
51
        private:
52
            float absolute_to_mps(int absolute_speed);
53
            bool setPenCallback(scoutsim::SetPen::Request&,
54
                                scoutsim::SetPen::Response&);
55
            void setMotors(const messages::set_motors::ConstPtr& msg);
56
            unsigned int rgb_to_grey(unsigned char r,
57
                                     unsigned char g,
58
                                     unsigned char b);
59
            bool isFront;
60
            
61
            int teleop_latch;
62

    
63
                wxBitmap *path_bitmap;
64
                bool ignore_behavior;
65
            
66
            //std::string current_teleop_scout;
67

    
68
            ros::NodeHandle node;
69

    
70
            wxImage emitter_image;
71
            wxBitmap emitter;
72

    
73
            Vector2 pos;
74
            float orient;
75

    
76
            // Each emitter has a unique id number, which is also displayed on its image.
77
            int emitter_id;
78

    
79
            float aperture;
80
            int distance;
81

    
82
            bool pen_on;
83
            bool emitter_visual_on;
84
            wxPen pen;
85

    
86
            ros::Publisher color_pub;
87
            ros::ServiceServer set_pen_srv;
88

    
89
            ros::WallTime last_command_time;
90
    };
91
    typedef boost::shared_ptr<Emitter> EmitterPtr;
92
}
93

    
94
#endif