root / scout / libscout / src / behaviors / Odometry.cpp @ 9a88eb2e
History | View | Annotate | Download (2.07 KB)
1 | f79fbce2 | Priya | |
---|---|---|---|
2 | #include "Odometry.h" |
||
3 | |||
4 | using namespace std; |
||
5 | |||
6 | /** Set up the odometry node and prepare communcations over ROS */
|
||
7 | d140fd71 | Yuyang | Odometry::Odometry(string scoutname, Sensors* sensors):Behavior(scoutname,
|
8 | "odometry", sensors)
|
||
9 | f79fbce2 | Priya | { |
10 | scout_pos = new pos;
|
||
11 | 3db79f25 | Priya | motor_fl_ticks = motor_fr_ticks = motor_bl_ticks = motor_br_ticks = 0;
|
12 | f79fbce2 | Priya | } |
13 | |||
14 | /** Query encoders and estimate position based on encoder reading */
|
||
15 | void Odometry::get_position()
|
||
16 | { |
||
17 | float left_dist, right_dist, total_dist, theta;
|
||
18 | |||
19 | encoder_readings scout_enc = encoders->query(); |
||
20 | 31be19a6 | Priya | motor_fl_dist = scout_enc.fl_ticks - motor_fl_ticks; |
21 | motor_fr_dist = scout_enc.fr_ticks - motor_fr_ticks; |
||
22 | motor_bl_dist = scout_enc.bl_ticks - motor_bl_ticks; |
||
23 | motor_br_dist = scout_enc.br_ticks - motor_br_ticks; |
||
24 | f79fbce2 | Priya | |
25 | 3db79f25 | Priya | ROS_INFO("fl %d fr %d bl %d br %d", scout_enc.fl_ticks, scout_enc.fr_ticks, scout_enc.bl_ticks, scout_enc.br_ticks);
|
26 | ROS_INFO("fl %d fr %d bl %d br %d", motor_fl_ticks, motor_fr_ticks, motor_bl_ticks, motor_br_ticks);
|
||
27 | ROS_INFO("fl %d fr %d bl %d br %d", motor_fl_dist, motor_fr_dist, motor_bl_dist, motor_br_dist);
|
||
28 | f79fbce2 | Priya | |
29 | 3db79f25 | Priya | // Get Left and Right distance
|
30 | left_dist = DIST_PER_TICK*(((float)(motor_fl_dist))/2.0 + |
||
31 | ((float)(motor_bl_dist))/2.0); |
||
32 | right_dist = DIST_PER_TICK*(((float)(motor_fr_dist))/2.0 + |
||
33 | ((float)(motor_br_dist))/2.0); |
||
34 | f79fbce2 | Priya | |
35 | 3db79f25 | Priya | total_dist = (left_dist)/2.0 + (right_dist)/2.0; |
36 | theta = scout_pos->theta + atan2(left_dist - right_dist, WHEEL_BASE); |
||
37 | |||
38 | ROS_INFO("l: %f r: %f theta: %f", left_dist, right_dist, theta);
|
||
39 | |||
40 | scout_pos->x += total_dist*sin(theta); |
||
41 | scout_pos->y += total_dist*cos(theta); |
||
42 | scout_pos->theta = fmod(theta, 2*M_PI);
|
||
43 | 31be19a6 | Priya | |
44 | //Save state for next time in.
|
||
45 | motor_fl_ticks = scout_enc.fl_ticks; |
||
46 | motor_fr_ticks = scout_enc.fr_ticks; |
||
47 | motor_bl_ticks = scout_enc.bl_ticks; |
||
48 | motor_br_ticks = scout_enc.br_ticks; |
||
49 | 3db79f25 | Priya | |
50 | |||
51 | f79fbce2 | Priya | return;
|
52 | } |
||
53 | |||
54 | void Odometry::run()
|
||
55 | { |
||
56 | while(ok())
|
||
57 | { |
||
58 | get_position(); |
||
59 | 31be19a6 | Priya | //TODO publish position
|
60 | ROS_INFO("Scout is at x: %f y: %f theta: %f\n", scout_pos->x, scout_pos->y, scout_pos->theta);
|
||
61 | f79fbce2 | Priya | } |
62 | } |