root / scout / scoutsim / src / emitter.cpp @ 2d21076d
History | View | Annotate | Download (4.4 KB)
1 |
/**
|
---|---|
2 |
BETA version of Emitter object for use in BOM simulator
|
3 |
*/
|
4 |
|
5 |
#include "emitter.h" |
6 |
|
7 |
#include <wx/wx.h> |
8 |
|
9 |
#define DEFAULT_PEN_R 0xb3 |
10 |
#define DEFAULT_PEN_G 0xb8 |
11 |
#define DEFAULT_PEN_B 0xff |
12 |
|
13 |
using namespace std; |
14 |
|
15 |
namespace scoutsim
|
16 |
{ |
17 |
/**
|
18 |
* The emitter object, which is responsible for refreshing itself and
|
19 |
* updating its position.
|
20 |
*
|
21 |
*/
|
22 |
Emitter::Emitter(const ros::NodeHandle& nh,
|
23 |
const wxImage& emitter_image,
|
24 |
const Vector2& pos,
|
25 |
wxBitmap *path_bitmap, |
26 |
float orient,
|
27 |
float aperture,
|
28 |
int distance)
|
29 |
: path_bitmap(path_bitmap) |
30 |
, ignore_behavior(false)
|
31 |
, node (nh) |
32 |
, emitter_image(emitter_image) |
33 |
, pos(pos) |
34 |
, orient(orient) |
35 |
, aperture(aperture) |
36 |
, distance(distance) |
37 |
, pen_on(true)
|
38 |
, pen(wxColour(DEFAULT_PEN_R, DEFAULT_PEN_G, DEFAULT_PEN_B)) |
39 |
{ |
40 |
pen.SetWidth(3);
|
41 |
emitter = wxBitmap(emitter_image); |
42 |
color_pub = node.advertise<Color>("color_sensor", 1); |
43 |
set_pen_srv = node.advertiseService("set_pen",
|
44 |
&Emitter::setPenCallback, |
45 |
this);
|
46 |
// Init latch
|
47 |
teleop_latch = 0;
|
48 |
} |
49 |
|
50 |
|
51 |
bool Emitter::setPenCallback(scoutsim::SetPen::Request& req,
|
52 |
scoutsim::SetPen::Response&) |
53 |
{ |
54 |
pen_on = !req.off; |
55 |
if (req.off)
|
56 |
{ |
57 |
return true; |
58 |
} |
59 |
|
60 |
wxPen pen(wxColour(req.r, req.g, req.b)); |
61 |
if (req.width != 0) |
62 |
{ |
63 |
pen.SetWidth(req.width); |
64 |
} |
65 |
|
66 |
pen = pen; |
67 |
return true; |
68 |
} |
69 |
|
70 |
// Scale to linesensor value
|
71 |
unsigned int Emitter::rgb_to_grey(unsigned char r, |
72 |
unsigned char g, |
73 |
unsigned char b) |
74 |
{ |
75 |
// Should be 0 to 255
|
76 |
unsigned int grey = ((unsigned int) r + (unsigned int) g + (unsigned int) b) / 3; |
77 |
|
78 |
/// @todo Convert to the proper range
|
79 |
return 255 - grey; |
80 |
} |
81 |
|
82 |
/// Sends back the position of this emitter so scoutsim can save
|
83 |
/// the world state
|
84 |
/// @todo remove dt param
|
85 |
geometry_msgs::Pose2D Emitter::update(double dt, wxMemoryDC& path_dc,
|
86 |
const wxImage& path_image,
|
87 |
const wxImage& lines_image,
|
88 |
const wxImage& walls_image,
|
89 |
wxColour background_color, |
90 |
world_state state) |
91 |
{ |
92 |
|
93 |
pos.x = min(max(pos.x, 0.0f), state.canvas_width); |
94 |
pos.y = min(max(pos.y, 0.0f), state.canvas_height); |
95 |
|
96 |
//int canvas_x = pos.x * PIX_PER_METER;
|
97 |
//int canvas_y = pos.y * PIX_PER_METER;
|
98 |
|
99 |
|
100 |
{ |
101 |
wxImage rotated_image = |
102 |
emitter_image.Rotate(orient - PI/2.0, |
103 |
wxPoint(emitter_image.GetWidth() / 2,
|
104 |
emitter_image.GetHeight() / 2),
|
105 |
false);
|
106 |
|
107 |
for (int y = 0; y < rotated_image.GetHeight(); ++y) |
108 |
{ |
109 |
for (int x = 0; x < rotated_image.GetWidth(); ++x) |
110 |
{ |
111 |
if (rotated_image.GetRed(x, y) == 255 |
112 |
&& rotated_image.GetBlue(x, y) == 255
|
113 |
&& rotated_image.GetGreen(x, y) == 255)
|
114 |
{ |
115 |
rotated_image.SetAlpha(x, y, 0);
|
116 |
} |
117 |
} |
118 |
} |
119 |
|
120 |
emitter = wxBitmap(rotated_image); |
121 |
} |
122 |
|
123 |
geometry_msgs::Pose2D my_pose; |
124 |
my_pose.x = pos.x; |
125 |
my_pose.y = pos.y; |
126 |
my_pose.theta = orient; |
127 |
|
128 |
return my_pose;
|
129 |
} |
130 |
|
131 |
geometry_msgs::Pose2D Emitter::get_pos() |
132 |
{ |
133 |
|
134 |
geometry_msgs::Pose2D my_pose; |
135 |
my_pose.x = pos.x; |
136 |
my_pose.y = pos.y; |
137 |
my_pose.theta = orient; |
138 |
|
139 |
return my_pose;
|
140 |
} |
141 |
|
142 |
void Emitter::paint(wxDC& dc)
|
143 |
{ |
144 |
wxSize emitter_size = wxSize(emitter.GetWidth(), emitter.GetHeight()); |
145 |
dc.DrawBitmap(emitter, pos.x * PIX_PER_METER - (emitter_size.GetWidth() / 2),
|
146 |
pos.y * PIX_PER_METER - (emitter_size.GetHeight() / 2), true); |
147 |
} |
148 |
|
149 |
void Emitter::set_emitter_visual(bool on) |
150 |
{ |
151 |
emitter_visual_on = on; |
152 |
} |
153 |
} |
154 |
|
155 |
/** @} */
|