scoutos / scout / libscout / src / MotorControl.h @ 1034f829
History | View | Annotate | Download (3.77 KB)
1 | c406f16b | Ben | /**
|
---|---|---|---|
2 | 0121ead7 | bwasserm | * Copyright (c) 2011 Colony Project
|
3 | c406f16b | Ben | *
|
4 | * Permission is hereby granted, free of charge, to any person
|
||
5 | * obtaining a copy of this software and associated documentation
|
||
6 | * files (the "Software"), to deal in the Software without
|
||
7 | * restriction, including without limitation the rights to use,
|
||
8 | * copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||
9 | * copies of the Software, and to permit persons to whom the
|
||
10 | * Software is furnished to do so, subject to the following
|
||
11 | * conditions:
|
||
12 | *
|
||
13 | * The above copyright notice and this permission notice shall be
|
||
14 | * included in all copies or substantial portions of the Software.
|
||
15 | *
|
||
16 | * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
|
||
17 | * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
|
||
18 | * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||
19 | * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
|
||
20 | * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
|
||
21 | * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||
22 | * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
|
||
23 | * OTHER DEALINGS IN THE SOFTWARE.
|
||
24 | c492be62 | Alex Zirbel | */
|
25 | c406f16b | Ben | |
26 | /**
|
||
27 | a8480867 | Alex Zirbel | * @file MotorControl.h
|
28 | c406f16b | Ben | * @brief Contains motor declarations and functions
|
29 | *
|
||
30 | * Contains functions and definitions for the use of
|
||
31 | * motors
|
||
32 | *
|
||
33 | * @author Colony Project, CMU Robotics Club
|
||
34 | a8480867 | Alex Zirbel | * @author Ben Wasserman
|
35 | * @author Alex Zirbel
|
||
36 | c406f16b | Ben | **/
|
37 | |||
38 | a8480867 | Alex Zirbel | #ifndef _MOTOR_CONTROL_H_
|
39 | #define _MOTOR_CONTROL_H_
|
||
40 | c406f16b | Ben | |
41 | a8480867 | Alex Zirbel | #include <ros/ros.h> |
42 | #include <motors/query_motors.h> |
||
43 | #include <motors/set_motors.h> |
||
44 | c406f16b | Ben | |
45 | cc558a8d | Alex Zirbel | #include "constants.h" |
46 | |||
47 | a8480867 | Alex Zirbel | /* Motor-specific defines */
|
48 | 0121ead7 | bwasserm | #define MOTOR_ALL 0xF |
49 | #define MOTOR_ALL_REV 0xF0 |
||
50 | #define MOTOR_NONE 0x0 |
||
51 | #define MOTOR_FL 0x8 |
||
52 | #define MOTOR_FR 0x4 |
||
53 | #define MOTOR_BL 0x2 |
||
54 | #define MOTOR_BR 0x1 |
||
55 | #define MOTOR_FL_REV 0x80 |
||
56 | #define MOTOR_FR_REV 0x40 |
||
57 | #define MOTOR_BL_REV 0x20 |
||
58 | #define MOTOR_BR_REV 0x10 |
||
59 | #define MOTOR_FRONT MOTOR_FL | MOTOR_FR
|
||
60 | #define MOTOR_BACK MOTOR_BR | MOTOR_BR
|
||
61 | #define MOTOR_LEFT MOTOR_FL | MOTOR_BL
|
||
62 | #define MOTOR_RIGHT MOTOR_FR | MOTOR_BR
|
||
63 | #define MOTOR_LEFT_REV MOTOR_FL_REV | MOTOR_BL_REV
|
||
64 | #define MOTOR_RIGHT_REV MOTOR_FR_REV | MOTOR_BR_REV
|
||
65 | #define MOTOR_LEFT_SPIN MOTOR_LEFT_REV | MOTOR_RIGHT
|
||
66 | #define MOTOR_RIGHT_SPIN MOTOR_LEFT | MOTOR_RIGHT_REV
|
||
67 | 2814387f | Alex Zirbel | |
68 | a8480867 | Alex Zirbel | #define MAXSPEED 255 |
69 | 0121ead7 | bwasserm | #define MOTOR_PERCENT 'p' |
70 | #define MOTOR_MMS 'm' |
||
71 | #define MOTOR_CMS 'c' |
||
72 | c9f87aaf | bwasserm | #define MOTOR_ABSOLUTE 'a' |
73 | 2814387f | Alex Zirbel | #define MOTOR_DEFAULT_UNIT MOTOR_PERCENT
|
74 | c406f16b | Ben | |
75 | a8480867 | Alex Zirbel | class MotorControl |
76 | { |
||
77 | public:
|
||
78 | /** Set up the motor node and prepare to communicate over ROS */
|
||
79 | c384dc7e | Alex Zirbel | MotorControl(const ros::NodeHandle& libscout_node,
|
80 | std::string scoutname); |
||
81 | a8480867 | Alex Zirbel | |
82 | 6761a531 | Priya | ~MotorControl(); |
83 | |||
84 | a8480867 | Alex Zirbel | /** Uses which to specify what to change, and sets all to same speed */
|
85 | void set(int which, float speed, char units=MOTOR_DEFAULT_UNIT); |
||
86 | |||
87 | /** Sets each side to a different speed */
|
||
88 | void set_sides(float speed_l, float speed_r, |
||
89 | 2814387f | Alex Zirbel | char units=MOTOR_DEFAULT_UNIT);
|
90 | a8480867 | Alex Zirbel | |
91 | /** Sets each motor speed individually */
|
||
92 | void set_each(int which, |
||
93 | 2814387f | Alex Zirbel | float speed_fl, float speed_fr, |
94 | float speed_bl, float speed_br, |
||
95 | char units=MOTOR_DEFAULT_UNIT);
|
||
96 | a8480867 | Alex Zirbel | |
97 | /** Requests the current motor speeds */
|
||
98 | float query(int which); |
||
99 | |||
100 | private:
|
||
101 | /** Error if which sets a motor to both forward and backward */
|
||
102 | void check_which_ok(int which); |
||
103 | |||
104 | float rel_to_abs(float rel_speed, int units); |
||
105 | float abs_to_rel(float abs_speed, int units); |
||
106 | |||
107 | /* Absolute speeds, but allowing fractions. Useful for PID, etc. */
|
||
108 | float motor_fl_speed;
|
||
109 | float motor_fr_speed;
|
||
110 | float motor_bl_speed;
|
||
111 | float motor_br_speed;
|
||
112 | |||
113 | /** ROS publisher and client declaration */
|
||
114 | ros::Publisher set_motors_pub; |
||
115 | ros::ServiceClient query_motors_client; |
||
116 | |||
117 | ros::NodeHandle node; |
||
118 | }; |
||
119 | c406f16b | Ben | |
120 | #endif
|