Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / motors / src / motors.cpp @ 126fea96

History | View | Annotate | Download (5.83 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
 * @defgroup motors Motors
37
 * @brief Functions for using the motors
38
 *
39
 * @{
40
 */
41

    
42
#include <ros/ros.h>
43
#include <cstdlib>
44
#include "motors.h"
45

    
46
using namespace std;
47

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

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

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

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

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

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

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

    
109
    speed = new_speed;
110

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

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

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

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

    
174
    ROS_DEBUG("Motor speeds set");
175
}
176

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

    
193
    ROS_DEBUG("Motor speeds queried");
194

    
195
    return true;
196
}
197

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

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

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

    
222
    ROS_INFO("Motors node ready.");
223
    ros::spin();
224

    
225
    return 0;
226
}
227

    
228
/** @} */