Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / scoutsim / src / emitter.h @ cda6b590

History | View | Annotate | Download (2.61 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_EM_APERTURE (PI * 0.05) // 9 degrees
28
#define BOM_EM_DISTANCE 5.0
29
#define BOM_REC_APERTURE (PI / 6) // 30 degrees
30
#define BOM_REC_DISTANCE 5.0
31

    
32
namespace scoutsim
33
{
34

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

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

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

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

    
65
                wxBitmap *path_bitmap;
66
                bool ignore_behavior;
67
            
68
            //std::string current_teleop_scout;
69

    
70
            ros::NodeHandle node;
71

    
72
            wxImage emitter_image;
73
            wxBitmap emitter;
74

    
75
            Vector2 pos;
76
            float orient;
77

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

    
81
            float aperture;
82
            int distance;
83

    
84
            bool pen_on;
85
            bool emitter_visual_on;
86
            wxPen pen;
87

    
88
            ros::Publisher color_pub;
89
            ros::ServiceServer set_pen_srv;
90

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

    
96
#endif