Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / libscout / src / libmotors.cpp @ 2814387f

History | View | Annotate | Download (6.32 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
/**
28
 * @file libmotors.cpp
29
 * @brief Contains motor declarations and functions
30
 * 
31
 * Contains functions and definitions for the use of
32
 * motors
33
 *
34
 * @author Colony Project, CMU Robotics Club
35
 **/
36

    
37
#include "libmotors.h"
38

    
39
/* ROS node created in libscout.cpp */
40
extern ros::NodeHandle node;
41

    
42
/** ROS publisher and client declaration */
43
ros::Publisher set_motors_publisher;
44
ros::ServiceClient query_motors_client;
45

    
46
/**
47
 * @brief Initialize the motors module of libscout.
48
 *
49
 * Initialize the libscout node as a publisher of set_motors and a client of
50
 * query_motors.
51
 */
52
void libmotors_init()
53
{
54
    set_motors_publisher =
55
        node.advertise<motors::set_motors>("set_motors", QUEUE_SIZE);
56
    query_motors_client =
57
        node.serviceClient<motors::query_motors>("query_motors");
58
}
59

    
60
/**
61
 * @brief Sets all the speeds according to the specificiation of which motors
62
 *        to set.
63
 *
64
 * @param which A bitmask of which motors need to be set.
65
 * @param speed The value to set the motors to.
66
 * @param units The units the speed is expressed in.
67
 * @return Function status
68
 */
69
int motors_set(int which, float speed, char units)
70
{
71
    float speed_fl, speed_fr, speed_bl, speed_br;
72
    speed_fl = speed_fr = speed_bl = speed_br = speed;
73

    
74
    if(which & MOTOR_FL_REV)
75
    {
76
        speed_fl = -speed;
77
    }
78
    if(which & MOTOR_FR_REV)
79
    {
80
        speed_fr = -speed;
81
    }
82
    if(which & MOTOR_BL_REV)
83
    {
84
        speed_bl = -speed;
85
    }
86
    if(which & MOTOR_BR_REV)
87
    {
88
        speed_br = -speed;
89
    }
90

    
91
    return motors_set_each(which, speed_fl, speed_fr, speed_bl, speed_br,
92
                           units);
93
}
94

    
95
/**
96
 * @brief Sets the left and right sides of scout to different speeds.
97
 *
98
 * @param speed_l The speed of both left motors.
99
 * @param speed_r The speed of both right motors.
100
 * @param units The units to set to.
101
 * @return Function status
102
 */
103
int motors_set_sides(float speed_l, float speed_r, char units)
104
{
105
    return motors_set_each(MOTOR_ALL, speed_l, speed_r, speed_l, speed_r,
106
                               units);
107
}
108

    
109
/**
110
 * @brief Set motor speeds
111
 * Sets the speeds of the motors as a percentage of top speed. Can selectively
112
 * select which motors to set, and which to remain at previous speed.
113
 *
114
 * @param which A bitmask of which motors should be set.
115
 * @param speed The speed the motors should be set to.
116
 * @param units Optional units for the speeds.
117
 * @return Function status
118
 */
119
int motors_set_each(int which,
120
                    float speed_fl, float speed_fr,
121
                    float speed_bl, float speed_br,
122
                    char units)
123
{
124
    check_which_ok(which);
125

    
126
    motors::set_motors msg;
127

    
128
    if(!ros::ok())
129
    {
130
        return LIB_ERROR;
131
    }
132

    
133
    /* Set all the speeds (the booleans in the set_motors message determine
134
     * which ones will be used) */
135
    msg.fl_speed = speed_fl;
136
    msg.fr_speed = speed_fr;
137
    msg.bl_speed = speed_bl;
138
    msg.br_speed = speed_br;
139

    
140
    /* Tell the motors node which motors need to be updated */
141
    msg.fl_set = msg.fr_set = msg.bl_set = msg.br_set = false;
142
    if(which & (MOTOR_FL | MOTOR_FL_REV))
143
    {
144
        msg.fl_set = true;
145
    }
146
    if(which & (MOTOR_FR | MOTOR_FR_REV))
147
    {
148
        msg.fr_set = true;
149
    }
150
    if(which & (MOTOR_BL | MOTOR_BL_REV))
151
    {
152
        msg.bl_set = true;
153
    }
154
    if(which & (MOTOR_BR | MOTOR_BR_REV))
155
    {
156
        msg.br_set = true;
157
    }
158

    
159
    /* Specify which units the speeds are given in */
160
    msg.units = units;
161

    
162
    /* Publishes message to set_motors topic */
163
    set_motors_publisher.publish(msg);
164
    ros::spinOnce();
165

    
166
    return LIB_OK;
167
}
168

    
169
/**
170
 * Double-checks the which variable to make sure the front and back
171
 * bits are not both set for a single motor.
172
 *
173
 * @param which The which motor specfication to check.
174
 */
175
void check_which_ok(int which)
176
{
177
    ROS_WARN_COND( ((which & MOTOR_FL) && (which & MOTOR_FL_REV)),
178
        "FL Motor set in both directions!");
179
    ROS_WARN_COND( ((which & MOTOR_FR) && (which & MOTOR_FR_REV)),
180
        "FR Motor set in both directions!");
181
    ROS_WARN_COND( ((which & MOTOR_BL) && (which & MOTOR_BL_REV)),
182
        "BL Motor set in both directions!");
183
    ROS_WARN_COND( ((which & MOTOR_BR) && (which & MOTOR_BR_REV)),
184
        "BR Motor set in both directions!");
185
}
186

    
187
/**
188
 * @brief Query the current speeds of the motors
189
 *
190
 * Sends a request to the query_motors service which will reply with the
191
 *  current speed of each motor.
192
 *
193
 * @todo Change so we can get multiple motor speeds with one call
194
 *
195
 * @param which A bitmask that will specify which motor speed should be
196
 *  returned
197
 * @return The speed of the selected motor, or LIB_ERR if no motor selected
198
 */
199
float motors_query(int which)
200
{
201
    motors::query_motors srv;
202
    if(query_motors_client.call(srv))
203
    {
204
        switch(which)
205
        {
206
            case MOTOR_FL:
207
                return srv.response.fl_speed;
208
            case MOTOR_FR:
209
                return srv.response.fr_speed;
210
            case MOTOR_BL:
211
                return srv.response.bl_speed;
212
            case MOTOR_BR:
213
                return srv.response.br_speed;
214
            default:
215
                ROS_WARN("Bad WHICH in motors_query.");
216
                return LIB_ERROR;
217
        }
218
    }
219
    else
220
    {
221
        ROS_ERROR("Failed to call service query_motors");
222
        return LIB_ERROR;
223
    }
224

    
225
    return 0;
226
}