Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / libscout / src / MotorControl.h @ cc558a8d

History | View | Annotate | Download (3.75 KB)

1
/**
2
 * Copyright (c) 2011 Colony Project
3
 * 
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
 **/
25

    
26
/**
27
 * @file MotorControl.h
28
 * @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
 * @author Ben Wasserman
35
 * @author Alex Zirbel
36
 **/
37

    
38
#ifndef _MOTOR_CONTROL_H_
39
#define _MOTOR_CONTROL_H_
40

    
41
#include <ros/ros.h>
42
#include <motors/query_motors.h>
43
#include <motors/set_motors.h>
44

    
45
#include "constants.h"
46

    
47
/* Motor-specific defines */
48
#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

    
68
#define MAXSPEED 255
69
#define MOTOR_PERCENT 'p'
70
#define MOTOR_MMS 'm'
71
#define MOTOR_CMS 'c'
72
#define MOTOR_ABSOLUTE 'a'
73
#define MOTOR_DEFAULT_UNIT MOTOR_PERCENT
74

    
75
class MotorControl
76
{
77
    public:
78
        /** Set up the motor node and prepare to communicate over ROS */
79
        MotorControl(const ros::NodeHandle& libscout_node,
80
                     std::string scoutname);
81

    
82
        /** Uses which to specify what to change, and sets all to same speed */
83
        void set(int which, float speed, char units=MOTOR_DEFAULT_UNIT);
84

    
85
        /** Sets each side to a different speed */
86
        void set_sides(float speed_l, float speed_r,
87
                     char units=MOTOR_DEFAULT_UNIT);
88

    
89
        /** Sets each motor speed individually */
90
        void set_each(int which,
91
                    float speed_fl, float speed_fr,
92
                    float speed_bl, float speed_br,
93
                    char units=MOTOR_DEFAULT_UNIT);
94
        
95
        /** Requests the current motor speeds */
96
        float query(int which);
97
    
98
    private:
99
        /** Error if which sets a motor to both forward and backward */
100
        void check_which_ok(int which);
101

    
102
        float rel_to_abs(float rel_speed, int units);
103
        float abs_to_rel(float abs_speed, int units);
104

    
105
        /* Absolute speeds, but allowing fractions. Useful for PID, etc. */
106
        float motor_fl_speed;
107
        float motor_fr_speed;
108
        float motor_bl_speed;
109
        float motor_br_speed;
110

    
111
        /** ROS publisher and client declaration */
112
        ros::Publisher set_motors_pub;
113
        ros::ServiceClient query_motors_client;
114

    
115
        ros::NodeHandle node;
116
};
117

    
118
#endif
119