root / scout / libscout / src / behaviors / Odometry.h @ 751d4f4f
History | View | Annotate | Download (1.49 KB)
1 | f79fbce2 | Priya | #ifndef _ODOMETRY_H_
|
---|---|---|---|
2 | #define _ODOMETRY_H_
|
||
3 | |||
4 | #include "../Behavior.h" |
||
5 | d140fd71 | Yuyang | #include "../Sensors.h" |
6 | 30a3768e | Priya | #include "messages/ScoutPosition.h" |
7 | bb64f5e5 | Priya | #include "../helper_classes/ScoutPosition.h" |
8 | f79fbce2 | Priya | |
9 | ddfeb111 | Priya | #define WHEEL_RADIUS .2 |
10 | f79fbce2 | Priya | #define WHEEL_CIRCUM (2*M_PI*WHEEL_RADIUS) |
11 | ddfeb111 | Priya | #define WHEEL_BASE 1.2 |
12 | #define ENCODER_COUNT (2*WHEEL_RADIUS*350*M_PI/WHEEL_BASE) |
||
13 | f79fbce2 | Priya | #define DIST_PER_TICK (WHEEL_CIRCUM/ENCODER_COUNT)
|
14 | |||
15 | 751d4f4f | Alex | class Odometry : public Behavior { |
16 | f79fbce2 | Priya | |
17 | 751d4f4f | Alex | public:
|
18 | f79fbce2 | Priya | |
19 | 751d4f4f | Alex | /** Set up the odometry node and prepare communcations over ROS */
|
20 | Odometry(std::string scoutname, Sensors* sensors); |
||
21 | f79fbce2 | Priya | |
22 | 751d4f4f | Alex | /** Set up the odometry node and prepare communcations over ROS */
|
23 | Odometry(std::string scoutname, std::string behavior_name, Sensors* sensors); |
||
24 | f79fbce2 | Priya | |
25 | 751d4f4f | Alex | /** Query encoders and estimate position based on encoder reading */
|
26 | void get_position();
|
||
27 | f79fbce2 | Priya | |
28 | 751d4f4f | Alex | /** Gets scout position and prints to screen */
|
29 | void run();
|
||
30 | 30a3768e | Priya | |
31 | 751d4f4f | Alex | protected:
|
32 | f79fbce2 | Priya | |
33 | 751d4f4f | Alex | pos* scout_pos; |
34 | 31be19a6 | Priya | |
35 | 751d4f4f | Alex | private:
|
36 | f79fbce2 | Priya | |
37 | 751d4f4f | Alex | /** ROS publisher and client declaration */
|
38 | ros::NodeHandle node; |
||
39 | ros::Publisher scout_position; |
||
40 | ros::ServiceClient query_encoders_client; |
||
41 | messages::ScoutPosition position; |
||
42 | 31be19a6 | Priya | |
43 | 751d4f4f | Alex | std::string name; |
44 | |||
45 | float msg_time_in;
|
||
46 | |||
47 | int motor_fl_dist;
|
||
48 | int motor_fr_dist;
|
||
49 | int motor_bl_dist;
|
||
50 | int motor_br_dist;
|
||
51 | |||
52 | unsigned int motor_fl_ticks; |
||
53 | unsigned int motor_fr_ticks; |
||
54 | unsigned int motor_bl_ticks; |
||
55 | unsigned int motor_br_ticks; |
||
56 | float scout_theta;
|
||
57 | f79fbce2 | Priya | }; |
58 | |||
59 | #endif |