Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / motors / src / motors.cpp @ 493cc515

History | View | Annotate | Download (5.82 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 motors.cpp
28
 * @brief Contains code to control the motors.
29
 *
30
 * Implementation of functions for motor use.
31
 *
32
 * @author Colony Project, CMU Robotics Club
33
 * @author Ben Wasserman
34
 * @author Tom Mullins
35
 */
36

    
37
#include <ros/ros.h>
38
#include <cstdlib>
39
#include "motors.h"
40

    
41
using namespace std;
42

    
43
/**
44
 * @defgroup motors Motors
45
 * @brief Functions for using the motors
46
 *
47
 * @{
48
 */
49

    
50
/**
51
 * @brief Motor constructor
52
 *
53
 * Opens device file and reads initial PWM value
54
 *
55
 * @param filename The name of the PWM device file
56
 */
57
Motor::Motor(int pwm_gpt, int in1_gpio, int in2_gpio)
58
{
59
    char buf[60];
60

    
61
    // open device files
62
    sprintf(buf, "/dev/pwm%d", pwm_gpt);
63
    fpwm.open(buf, ios::out);
64
    sprintf(buf, "/sys/class/gpio/gpio%d/value", in1_gpio);
65
    fin1.open(buf, ios::out);
66
    sprintf(buf, "/sys/class/gpio/gpio%d/value", in2_gpio);
67
    fin2.open(buf, ios::out);
68

    
69
    /* I set speed to 0 here rather than reading in what the current speed is
70
     * because the pwm driver does not support seeking in the device files.
71
     * Doing both reading and writing causes fpwm to attempt seeking, which
72
     * fails, causing fpwm to refuse to do any more io. So, we can only write.
73
     */
74
    speed = 0;
75

    
76
    // ensure we are in a consistent state by writing to hardware
77
    set_speed(speed);
78
}
79

    
80
/**
81
 * @brief Motor destructor
82
 *
83
 * Sets the motor's speed to zero in preparation for the node exiting
84
 */
85
Motor::~Motor()
86
{
87
    set_speed(0);
88
}
89

    
90
/**
91
 * @brief Returns current motor speed
92
 *
93
 * Note that this doesn't read from the hardware
94
 */
95
int Motor::get_speed()
96
{
97
    return speed;
98
}
99

    
100
/**
101
 * @brief Sets motor speed
102
 *
103
 * This will set the member this->speed and write the new speed to the hardware
104
 *
105
 * @param new_speed The speed to set, between +/- MAXSPEED inclusive
106
 */
107
void Motor::set_speed(int new_speed)
108
{
109
    int pwm, in1, in2;
110

    
111
    speed = new_speed;
112

    
113
    // convert to hardware units
114
    if (speed == 0)
115
    {
116
        /// @todo should this be off (00) or short brake (11)?
117
        pwm = 0;
118
        in1 = 0;
119
        in2 = 0;
120
    }
121
    else if (speed > 0)
122
    {
123
        // CW
124
        pwm = speed;
125
        in1 = 1;
126
        in2 = 0;
127
    }
128
    else
129
    {
130
        // CCW
131
        pwm = -speed;
132
        in1 = 0;
133
        in2 = 1;
134
    }
135

    
136
    // write to hardware
137
    fpwm << pwm << flush;
138
    fin1 << in1 << flush;
139
    fin2 << in2 << flush;
140
}
141

    
142
/// @todo change these to the correct motor locations / directions
143
// Motor state variables
144
static Motor motor_fl( 8, 70, 71);
145
static Motor motor_fr( 9, 72, 73);
146
static Motor motor_bl(11, 74, 75);
147
static Motor motor_br(10, 76, 77);
148

    
149
/**
150
 * @brief Sets motor speed
151
 *
152
 * Sets the motor speeds based on subscription to the set_motors topic.
153
 *
154
 * @param msg The message from the set_motors topic, containing speeds and
155
 *  motor configuration settings.
156
 */
157
void motors_set(const motors::set_motors::ConstPtr& msg)
158
{
159
    if(msg->fl_set)
160
    {
161
        motor_fl.set_speed(msg->fl_speed);
162
    }
163
    if(msg->fr_set)
164
    {
165
        motor_fr.set_speed(msg->fr_speed);
166
    }
167
    if(msg->bl_set)
168
    {
169
        motor_bl.set_speed(msg->bl_speed);
170
    }
171
    if(msg->br_set)
172
    {
173
        motor_br.set_speed(msg->br_speed);
174
    }
175

    
176
    ROS_DEBUG("Motor speeds set");
177
}
178

    
179
/**
180
 * @brief Outputs current motor speeds
181
 *
182
 * Serves the service query_motors by responding to service requests with the
183
 * speeds of the motors.
184
 * @param req The request. The only field is the units requested.
185
 * @param res The response. The fields will be filled with values.
186
 */
187
bool motors_query(motors::query_motors::Request &req,
188
                  motors::query_motors::Response &res)
189
{
190
    res.fl_speed = motor_fl.get_speed();
191
    res.fr_speed = motor_fr.get_speed();
192
    res.bl_speed = motor_bl.get_speed();
193
    res.br_speed = motor_br.get_speed();
194

    
195
    ROS_DEBUG("Motor speeds queried");
196

    
197
    return true;
198
}
199

    
200
/**
201
 * @brief Motors driver. This is a ROS node that controls motor speeds.
202
 *
203
 * This is the main function for the motors node. It is run when the node
204
 * starts and initializes the motors. It then subscribes to the
205
 * set_motors, and set_motor_speeds topics, and advertises the
206
 * query_motors service.
207
 * 
208
 * @param argc The number of command line arguments (should be 1)
209
 * @param argv The array of command line arguments
210
 */
211
int main(int argc, char **argv)
212
{
213
    /* Initialize in ROS the motors driver node */
214
    ros::init(argc, argv, "motors_driver");
215

    
216
    /* Advertise that this serves the query_motors service */
217
    ros::NodeHandle node;
218
    ros::ServiceServer service = node.advertiseService("query_motors",
219
                                                       motors_query);
220

    
221
    /* Subscribe to the set_motors topic */
222
    ros::Subscriber sub0 = node.subscribe("set_motors", QUEUE_SIZE, motors_set);
223

    
224
    ROS_INFO("Motors node ready.");
225
    ros::spin();
226

    
227
    return 0;
228
}
229

    
230
/** @} */