Revision af0d9743
ID | af0d974309704bd4784c74078aea0851fe280f91 |
Added template linesensors to scoutsim
scout/scoutsim/CMakeLists.txt | ||
---|---|---|
36 | 36 |
#rosbuild_add_executable(turtle_teleop_key tutorials/teleop_turtle_key.cpp) |
37 | 37 |
#rosbuild_add_executable(draw_square tutorials/draw_square.cpp) |
38 | 38 |
#rosbuild_add_executable(mimic tutorials/mimic.cpp) |
39 |
rosbuild_add_executable(scout_teleop src/scout_teleop.cpp) |
|
40 |
rosbuild_add_executable(scout_teleop_userinput src/scout_teleop_userinput.cpp) |
|
39 |
#rosbuild_add_executable(scout_teleop src/scout_teleop.cpp) |
|
40 |
#rosbuild_add_executable(scout_teleop_userinput src/scout_teleop_userinput.cpp) |
scout/scoutsim/manifest.xml | ||
---|---|---|
15 | 15 |
<depend package="std_srvs"/> |
16 | 16 |
<depend package="motors" /> |
17 | 17 |
<depend package="encoders" /> |
18 |
<depend package="linesensor" /> |
|
18 | 19 |
<depend package="geometry_msgs" /> |
19 | 20 |
|
20 | 21 |
<rosdep name="wxwidgets"/> |
scout/scoutsim/src/scout.cpp | ||
---|---|---|
53 | 53 |
#define DEFAULT_PEN_G 0xb8 |
54 | 54 |
#define DEFAULT_PEN_B 0xff |
55 | 55 |
|
56 |
using namespace std; |
|
57 |
|
|
56 | 58 |
namespace scoutsim |
57 | 59 |
{ |
58 | 60 |
Scout::Scout(const ros::NodeHandle& nh, |
... | ... | |
89 | 91 |
&Scout::query_encoders_callback, |
90 | 92 |
this); |
91 | 93 |
|
94 |
query_linesensor_srv = |
|
95 |
node.advertiseService("query_linesensor", |
|
96 |
&Scout::query_linesensor_callback, |
|
97 |
this); |
|
98 |
|
|
92 | 99 |
meter = scout.GetHeight(); |
93 | 100 |
} |
94 | 101 |
|
... | ... | |
156 | 163 |
return true; |
157 | 164 |
} |
158 | 165 |
|
166 |
bool Scout::query_linesensor_callback(linesensor::query_linesensor::Request&, |
|
167 |
linesensor::query_linesensor::Response& res) |
|
168 |
{ |
|
169 |
vector<unsigned int> readings; |
|
170 |
|
|
171 |
for (unsigned int i = 0; i < 8; i++) |
|
172 |
{ |
|
173 |
readings.push_back(8 - i); |
|
174 |
} |
|
175 |
|
|
176 |
res.readings = readings; |
|
177 |
|
|
178 |
return true; |
|
179 |
} |
|
180 |
|
|
159 | 181 |
/// Sends back the position of this scout so scoutsim can save |
160 | 182 |
/// the world state |
161 | 183 |
geometry_msgs::Pose2D Scout::update(double dt, wxMemoryDC& path_dc, |
... | ... | |
193 | 215 |
ROS_WARN("Oh no! I hit the wall! (Clamping from [x=%f, y=%f])", pos.x, pos.y); |
194 | 216 |
} |
195 | 217 |
|
196 |
pos.x = std::min(std::max(pos.x, 0.0f), state.canvas_width);
|
|
197 |
pos.y = std::min(std::max(pos.y, 0.0f), state.canvas_height);
|
|
218 |
pos.x = min(max(pos.x, 0.0f), state.canvas_width);
|
|
219 |
pos.y = min(max(pos.y, 0.0f), state.canvas_height);
|
|
198 | 220 |
|
199 | 221 |
int canvas_x = pos.x * meter; |
200 | 222 |
int canvas_y = pos.y * meter; |
scout/scoutsim/src/scout.h | ||
---|---|---|
49 | 49 |
#define _SCOUTSIM_SCOUT_H_ |
50 | 50 |
|
51 | 51 |
#include <ros/ros.h> |
52 |
#include <vector> |
|
52 | 53 |
#include <boost/shared_ptr.hpp> |
53 | 54 |
|
54 | 55 |
#include <motors/set_motors.h> |
55 | 56 |
#include <encoders/query_encoders.h> |
57 |
#include <linesensor/query_linesensor.h> |
|
56 | 58 |
|
57 | 59 |
#include <scoutsim/Pose.h> |
58 | 60 |
#include <scoutsim/SetPen.h> |
... | ... | |
118 | 120 |
scoutsim::SetPen::Response&); |
119 | 121 |
bool query_encoders_callback(encoders::query_encoders::Request&, |
120 | 122 |
encoders::query_encoders::Response&); |
123 |
bool query_linesensor_callback(linesensor::query_linesensor::Request&, |
|
124 |
linesensor::query_linesensor::Response&); |
|
121 | 125 |
|
122 | 126 |
ros::NodeHandle node; |
123 | 127 |
|
... | ... | |
152 | 156 |
ros::Publisher color_pub; |
153 | 157 |
ros::ServiceServer set_pen_srv; |
154 | 158 |
ros::ServiceServer query_encoders_srv; |
159 |
ros::ServiceServer query_linesensor_srv; |
|
155 | 160 |
|
156 | 161 |
ros::WallTime last_command_time; |
157 | 162 |
|
Also available in: Unified diff