Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / scoutsim / src / emitter.h @ 2d21076d

History | View | Annotate | Download (2.45 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
namespace scoutsim
28
{
29

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

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

    
44
            geometry_msgs::Pose2D get_pos();
45
            void paint(wxDC& dc);
46
            void set_emitter_visual(bool on);
47

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

    
60
                wxBitmap *path_bitmap;
61
                bool ignore_behavior;
62
            
63
            //std::string current_teleop_scout;
64

    
65
            ros::NodeHandle node;
66

    
67
            wxImage emitter_image;
68
            wxBitmap emitter;
69

    
70
            Vector2 pos;
71
            float orient;
72

    
73
            // Each emitter has a unique id number, which is also displayed on its image.
74
            int emitter_id;
75

    
76
            float aperture;
77
            int distance;
78

    
79
            bool pen_on;
80
            bool emitter_visual_on;
81
            wxPen pen;
82

    
83
            ros::Publisher color_pub;
84
            ros::ServiceServer set_pen_srv;
85

    
86
            ros::WallTime last_command_time;
87
    };
88
    typedef boost::shared_ptr<Emitter> EmitterPtr;
89
}
90

    
91
#endif