root / scout / motors / src / motors.cpp @ 560d2317
History | View | Annotate | Download (5.56 KB)
1 | c406f16b | Ben | /**
|
---|---|---|---|
2 | 0121ead7 | bwasserm | * Copyright (c) 2011 Colony Project
|
3 | c406f16b | Ben | *
|
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 | c492be62 | Alex Zirbel | */
|
25 | c406f16b | Ben | |
26 | /**
|
||
27 | * @file motors.cpp
|
||
28 | 18e2028b | Alex | * @brief Contains code to control the motors.
|
29 | c406f16b | Ben | *
|
30 | * Implementation of functions for motor use.
|
||
31 | *
|
||
32 | * @author Colony Project, CMU Robotics Club
|
||
33 | 3ec16d35 | Ben Wasserman | * @author Ben Wasserman
|
34 | 560d2317 | Tom Mullins | * @author Tom Mullins
|
35 | 9b11c5b3 | Alex Zirbel | */
|
36 | c406f16b | Ben | |
37 | a8480867 | Alex Zirbel | #include <ros/ros.h> |
38 | c406f16b | Ben | #include <cstdlib> |
39 | a8480867 | Alex Zirbel | #include "motors.h" |
40 | c406f16b | Ben | |
41 | cc9e9213 | Tom Mullins | using namespace std; |
42 | |||
43 | c406f16b | Ben | /**
|
44 | * @defgroup motors Motors
|
||
45 | * @brief Functions for using the motors
|
||
46 | *
|
||
47 | 18e2028b | Alex | * @{
|
48 | 9b11c5b3 | Alex Zirbel | */
|
49 | c406f16b | Ben | |
50 | 560d2317 | Tom Mullins | /**
|
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 | c9f87aaf | bwasserm | */
|
57 | 560d2317 | Tom Mullins | 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 | 0121ead7 | bwasserm | |
95 | 560d2317 | Tom Mullins | // 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 | cc9e9213 | Tom Mullins | |
159 | 18e2028b | Alex | /**
|
160 | * @brief Sets motor speed
|
||
161 | c406f16b | Ben | *
|
162 | * Sets the motor speeds based on subscription to the set_motors topic.
|
||
163 | *
|
||
164 | 18e2028b | Alex | * @param msg The message from the set_motors topic, containing speeds and
|
165 | c406f16b | Ben | * motor configuration settings.
|
166 | */
|
||
167 | 18e2028b | Alex | void motors_set(const motors::set_motors::ConstPtr& msg) |
168 | { |
||
169 | 2814387f | Alex Zirbel | if(msg->fl_set)
|
170 | c9f87aaf | bwasserm | { |
171 | 560d2317 | Tom Mullins | motor_fl.set_speed(msg->fl_speed); |
172 | c9f87aaf | bwasserm | } |
173 | 2814387f | Alex Zirbel | if(msg->fr_set)
|
174 | c9f87aaf | bwasserm | { |
175 | 560d2317 | Tom Mullins | motor_fr.set_speed(msg->fr_speed); |
176 | c9f87aaf | bwasserm | } |
177 | 2814387f | Alex Zirbel | if(msg->bl_set)
|
178 | c9f87aaf | bwasserm | { |
179 | 560d2317 | Tom Mullins | motor_bl.set_speed(msg->bl_speed); |
180 | c9f87aaf | bwasserm | } |
181 | 2814387f | Alex Zirbel | if(msg->br_set)
|
182 | c9f87aaf | bwasserm | { |
183 | 560d2317 | Tom Mullins | motor_br.set_speed(msg->br_speed); |
184 | c9f87aaf | bwasserm | } |
185 | |||
186 | 2814387f | Alex Zirbel | ROS_DEBUG("Motor speeds set");
|
187 | c406f16b | Ben | } |
188 | |||
189 | 18e2028b | Alex | /**
|
190 | * @brief Outputs current motor speeds
|
||
191 | c406f16b | Ben | *
|
192 | * Serves the service query_motors by responding to service requests with the
|
||
193 | * speeds of the motors.
|
||
194 | c9f87aaf | bwasserm | * @param req The request. The only field is the units requested.
|
195 | 18e2028b | Alex | * @param res The response. The fields will be filled with values.
|
196 | c406f16b | Ben | */
|
197 | bool motors_query(motors::query_motors::Request &req,
|
||
198 | 18e2028b | Alex | motors::query_motors::Response &res) |
199 | { |
||
200 | 560d2317 | Tom Mullins | 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 | 18e2028b | Alex | |
205 | ROS_DEBUG("Motor speeds queried");
|
||
206 | a8480867 | Alex Zirbel | |
207 | 18e2028b | Alex | 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 | 9b11c5b3 | Alex Zirbel | */
|
221 | 18e2028b | Alex | 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 | 2814387f | Alex Zirbel | ros::NodeHandle node; |
228 | ros::ServiceServer service = node.advertiseService("query_motors",
|
||
229 | motors_query); |
||
230 | 18e2028b | Alex | |
231 | /* Subscribe to the set_motors topic */
|
||
232 | 2814387f | Alex Zirbel | ros::Subscriber sub0 = node.subscribe("set_motors", QUEUE_SIZE, motors_set);
|
233 | 18e2028b | Alex | |
234 | a8480867 | Alex Zirbel | ROS_INFO("Motors node ready.");
|
235 | 18e2028b | Alex | ros::spin(); |
236 | c406f16b | Ben | |
237 | 18e2028b | Alex | return 0; |
238 | c406f16b | Ben | } |
239 | |||
240 | 9b11c5b3 | Alex Zirbel | /** @} */ |