root / scout / motors / src / motors.cpp @ 560d2317
History | View | Annotate | Download (5.56 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(const char* pwmfile, const char* in1file, const char* in2file) |
58 |
: fpwm(pwmfile), fin1(in1file), fin2(in2file) |
59 |
{ |
60 |
int pwm, in1, in2;
|
61 |
|
62 |
// read current values from device files
|
63 |
fpwm >> pwm; |
64 |
fin1 >> in1; |
65 |
fin2 >> in2; |
66 |
|
67 |
// convert to our speed units
|
68 |
if (in1)
|
69 |
{ |
70 |
if (in2)
|
71 |
{ |
72 |
// short brake
|
73 |
speed = 0;
|
74 |
} |
75 |
else
|
76 |
{ |
77 |
// CW
|
78 |
speed = pwm; |
79 |
} |
80 |
} |
81 |
else
|
82 |
{ |
83 |
if (in2)
|
84 |
{ |
85 |
// CCW
|
86 |
speed = -pwm; |
87 |
} |
88 |
else
|
89 |
{ |
90 |
// off
|
91 |
speed = 0;
|
92 |
} |
93 |
} |
94 |
|
95 |
// ensure we are in a consistent state by writing back to hardware
|
96 |
set_speed(speed); |
97 |
} |
98 |
|
99 |
/**
|
100 |
* @brief Returns current motor speed
|
101 |
*
|
102 |
* Note that this doesn't read from the hardware
|
103 |
*/
|
104 |
int Motor::get_speed()
|
105 |
{ |
106 |
return speed;
|
107 |
} |
108 |
|
109 |
/**
|
110 |
* @brief Sets motor speed
|
111 |
*
|
112 |
* This will set the member this->speed and write the new speed to the hardware
|
113 |
*
|
114 |
* @param new_speed The speed to set, between +/- MAXSPEED inclusive
|
115 |
*/
|
116 |
void Motor::set_speed(int new_speed) |
117 |
{ |
118 |
int pwm, in1, in2;
|
119 |
|
120 |
speed = new_speed; |
121 |
|
122 |
// convert to hardware units
|
123 |
if (speed == 0) |
124 |
{ |
125 |
/// @todo should this be off (00) or short brake (11)?
|
126 |
pwm = 0;
|
127 |
in1 = 0;
|
128 |
in2 = 0;
|
129 |
} |
130 |
else if (speed > 0) |
131 |
{ |
132 |
// CW
|
133 |
pwm = speed; |
134 |
in1 = 1;
|
135 |
in2 = 0;
|
136 |
} |
137 |
else
|
138 |
{ |
139 |
// CCW
|
140 |
pwm = -speed; |
141 |
in1 = 0;
|
142 |
in2 = 1;
|
143 |
} |
144 |
|
145 |
// write to hardware
|
146 |
fpwm << pwm; |
147 |
fin1 << in1; |
148 |
fin2 << in2; |
149 |
} |
150 |
|
151 |
/// @todo change these to the correct files
|
152 |
/// @todo also, a problem: gpio can only be done as root!
|
153 |
// Motor state variables
|
154 |
static Motor motor_fl("/dev/pwm8", "/dev/null", "/dev/null"); |
155 |
static Motor motor_fr("/dev/pwm9", "/dev/null", "/dev/null"); |
156 |
static Motor motor_bl("/dev/pwm10", "/dev/null", "/dev/null"); |
157 |
static Motor motor_br("/dev/pwm11", "/dev/null", "/dev/null"); |
158 |
|
159 |
/**
|
160 |
* @brief Sets motor speed
|
161 |
*
|
162 |
* Sets the motor speeds based on subscription to the set_motors topic.
|
163 |
*
|
164 |
* @param msg The message from the set_motors topic, containing speeds and
|
165 |
* motor configuration settings.
|
166 |
*/
|
167 |
void motors_set(const motors::set_motors::ConstPtr& msg) |
168 |
{ |
169 |
if(msg->fl_set)
|
170 |
{ |
171 |
motor_fl.set_speed(msg->fl_speed); |
172 |
} |
173 |
if(msg->fr_set)
|
174 |
{ |
175 |
motor_fr.set_speed(msg->fr_speed); |
176 |
} |
177 |
if(msg->bl_set)
|
178 |
{ |
179 |
motor_bl.set_speed(msg->bl_speed); |
180 |
} |
181 |
if(msg->br_set)
|
182 |
{ |
183 |
motor_br.set_speed(msg->br_speed); |
184 |
} |
185 |
|
186 |
ROS_DEBUG("Motor speeds set");
|
187 |
} |
188 |
|
189 |
/**
|
190 |
* @brief Outputs current motor speeds
|
191 |
*
|
192 |
* Serves the service query_motors by responding to service requests with the
|
193 |
* speeds of the motors.
|
194 |
* @param req The request. The only field is the units requested.
|
195 |
* @param res The response. The fields will be filled with values.
|
196 |
*/
|
197 |
bool motors_query(motors::query_motors::Request &req,
|
198 |
motors::query_motors::Response &res) |
199 |
{ |
200 |
res.fl_speed = motor_fl.get_speed(); |
201 |
res.fr_speed = motor_fr.get_speed(); |
202 |
res.bl_speed = motor_bl.get_speed(); |
203 |
res.br_speed = motor_br.get_speed(); |
204 |
|
205 |
ROS_DEBUG("Motor speeds queried");
|
206 |
|
207 |
return true; |
208 |
} |
209 |
|
210 |
/**
|
211 |
* @brief Motors driver. This is a ROS node that controls motor speeds.
|
212 |
*
|
213 |
* This is the main function for the motors node. It is run when the node
|
214 |
* starts and initializes the motors. It then subscribes to the
|
215 |
* set_motors, and set_motor_speeds topics, and advertises the
|
216 |
* query_motors service.
|
217 |
*
|
218 |
* @param argc The number of command line arguments (should be 1)
|
219 |
* @param argv The array of command line arguments
|
220 |
*/
|
221 |
int main(int argc, char **argv) |
222 |
{ |
223 |
/* Initialize in ROS the motors driver node */
|
224 |
ros::init(argc, argv, "motors_driver");
|
225 |
|
226 |
/* Advertise that this serves the query_motors service */
|
227 |
ros::NodeHandle node; |
228 |
ros::ServiceServer service = node.advertiseService("query_motors",
|
229 |
motors_query); |
230 |
|
231 |
/* Subscribe to the set_motors topic */
|
232 |
ros::Subscriber sub0 = node.subscribe("set_motors", QUEUE_SIZE, motors_set);
|
233 |
|
234 |
ROS_INFO("Motors node ready.");
|
235 |
ros::spin(); |
236 |
|
237 |
return 0; |
238 |
} |
239 |
|
240 |
/** @} */
|