Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / motors / src / motors.cpp @ 7e9a19f4

History | View | Annotate | Download (5.6 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
  int pwm, in1, in2;
61

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

    
70
  // read current values from device files
71
  fpwm >> pwm;
72
  fin1 >> in1;
73
  fin2 >> in2;
74

    
75
  // convert to our speed units
76
  if (in1)
77
  {
78
    if (in2)
79
    {
80
      // short brake
81
      speed = 0;
82
    }
83
    else
84
    {
85
      // CW
86
      speed = pwm;
87
    }
88
  }
89
  else
90
  {
91
    if (in2)
92
    {
93
      // CCW
94
      speed = -pwm;
95
    }
96
    else
97
    {
98
      // off
99
      speed = 0;
100
    }
101
  }
102

    
103
  // ensure we are in a consistent state by writing back to hardware
104
  set_speed(speed);
105
}
106

    
107
/**
108
 * @brief Returns current motor speed
109
 *
110
 * Note that this doesn't read from the hardware
111
 */
112
int Motor::get_speed()
113
{
114
  return speed;
115
}
116

    
117
/**
118
 * @brief Sets motor speed
119
 *
120
 * This will set the member this->speed and write the new speed to the hardware
121
 *
122
 * @param new_speed The speed to set, between +/- MAXSPEED inclusive
123
 */
124
void Motor::set_speed(int new_speed)
125
{
126
  int pwm, in1, in2;
127

    
128
  speed = new_speed;
129

    
130
  // convert to hardware units
131
  if (speed == 0)
132
  {
133
    /// @todo should this be off (00) or short brake (11)?
134
    pwm = 0;
135
    in1 = 0;
136
    in2 = 0;
137
  }
138
  else if (speed > 0)
139
  {
140
    // CW
141
    pwm = speed;
142
    in1 = 1;
143
    in2 = 0;
144
  }
145
  else
146
  {
147
    // CCW
148
    pwm = -speed;
149
    in1 = 0;
150
    in2 = 1;
151
  }
152

    
153
  // write to hardware
154
  fpwm << pwm << flush;
155
  fin1 << in1 << flush;
156
  fin2 << in2 << flush;
157
}
158

    
159
/// @todo change these to the correct motor locations
160
// Motor state variables
161
static Motor motor_fl( 8, 70, 71);
162
static Motor motor_fr( 9, 72, 73);
163
static Motor motor_bl(11, 74, 75);
164
static Motor motor_br(10, 76, 77);
165

    
166
/**
167
 * @brief Sets motor speed
168
 *
169
 * Sets the motor speeds based on subscription to the set_motors topic.
170
 *
171
 * @param msg The message from the set_motors topic, containing speeds and
172
 *  motor configuration settings.
173
 */
174
void motors_set(const motors::set_motors::ConstPtr& msg)
175
{
176
    if(msg->fl_set)
177
    {
178
      motor_fl.set_speed(msg->fl_speed);
179
    }
180
    if(msg->fr_set)
181
    {
182
      motor_fr.set_speed(msg->fr_speed);
183
    }
184
    if(msg->bl_set)
185
    {
186
      motor_bl.set_speed(msg->bl_speed);
187
    }
188
    if(msg->br_set)
189
    {
190
      motor_br.set_speed(msg->br_speed);
191
    }
192

    
193
    ROS_DEBUG("Motor speeds set");
194
}
195

    
196
/**
197
 * @brief Outputs current motor speeds
198
 *
199
 * Serves the service query_motors by responding to service requests with the
200
 * speeds of the motors.
201
 * @param req The request. The only field is the units requested.
202
 * @param res The response. The fields will be filled with values.
203
 */
204
bool motors_query(motors::query_motors::Request &req,
205
                  motors::query_motors::Response &res)
206
{
207
    res.fl_speed = motor_fl.get_speed();
208
    res.fr_speed = motor_fr.get_speed();
209
    res.bl_speed = motor_bl.get_speed();
210
    res.br_speed = motor_br.get_speed();
211

    
212
    ROS_DEBUG("Motor speeds queried");
213

    
214
    return true;
215
}
216

    
217
/**
218
 * @brief Motors driver. This is a ROS node that controls motor speeds.
219
 *
220
 * This is the main function for the motors node. It is run when the node
221
 * starts and initializes the motors. It then subscribes to the
222
 * set_motors, and set_motor_speeds topics, and advertises the
223
 * query_motors service.
224
 * 
225
 * @param argc The number of command line arguments (should be 1)
226
 * @param argv The array of command line arguments
227
 */
228
int main(int argc, char **argv)
229
{
230
    /* Initialize in ROS the motors driver node */
231
    ros::init(argc, argv, "motors_driver");
232

    
233
    /* Advertise that this serves the query_motors service */
234
    ros::NodeHandle node;
235
    ros::ServiceServer service = node.advertiseService("query_motors",
236
                                                       motors_query);
237

    
238
    /* Subscribe to the set_motors topic */
239
    ros::Subscriber sub0 = node.subscribe("set_motors", QUEUE_SIZE, motors_set);
240

    
241
    ROS_INFO("Motors node ready.");
242
    ros::spin();
243

    
244
    return 0;
245
}
246

    
247
/** @} */