Revision 30a3768e scout/libscout/src/behaviors/Odometry.cpp
| scout/libscout/src/behaviors/Odometry.cpp | ||
|---|---|---|
| 7 | 7 |
Odometry::Odometry(string scoutname, Sensors* sensors):Behavior(scoutname, |
| 8 | 8 |
"odometry", sensors) |
| 9 | 9 |
{
|
| 10 |
name = scoutname; |
|
| 10 | 11 |
scout_pos = new pos; |
| 11 | 12 |
motor_fl_ticks = motor_fr_ticks = motor_bl_ticks = motor_br_ticks = 0; |
| 12 | 13 |
} |
| ... | ... | |
| 53 | 54 |
|
| 54 | 55 |
void Odometry::run() |
| 55 | 56 |
{
|
| 57 |
scout_position = node.advertise< ::messages::ScoutPosition>(name+"/position", 1000); |
|
| 58 |
|
|
| 56 | 59 |
while(ok()) |
| 57 | 60 |
{
|
| 58 | 61 |
get_position(); |
| 59 |
//TODO publish position |
|
| 62 |
|
|
| 63 |
position.name = name; |
|
| 64 |
position.x = scout_pos->x; |
|
| 65 |
position.y = scout_pos->y; |
|
| 66 |
position.theta = scout_pos->theta; |
|
| 67 |
scout_position.publish(position); |
|
| 68 |
|
|
| 60 | 69 |
ROS_INFO("Scout is at x: %f y: %f theta: %f\n", scout_pos->x, scout_pos->y, scout_pos->theta);
|
| 61 | 70 |
} |
| 62 | 71 |
} |
Also available in: Unified diff