root / scout / motors / src / motors.cpp @ 6ebee82c
History | View | Annotate | Download (5.84 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 | ed37d345 | Tom Mullins | Motor::Motor(int pwm_gpt, int in1_gpio, int in2_gpio) |
58 | 560d2317 | Tom Mullins | { |
59 | fcd68ec1 | Tom Mullins | 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 | 560d2317 | Tom Mullins | } |
79 | |||
80 | /**
|
||
81 | 8913c26d | Tom Mullins | * @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 | 560d2317 | Tom Mullins | * @brief Returns current motor speed
|
92 | *
|
||
93 | * Note that this doesn't read from the hardware
|
||
94 | */
|
||
95 | int Motor::get_speed()
|
||
96 | { |
||
97 | fcd68ec1 | Tom Mullins | return speed;
|
98 | 560d2317 | Tom Mullins | } |
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 | fcd68ec1 | Tom Mullins | 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 | 560d2317 | Tom Mullins | } |
141 | |||
142 | 8913c26d | Tom Mullins | /// @todo change these to the correct motor locations / directions
|
143 | 560d2317 | Tom Mullins | // Motor state variables
|
144 | ed37d345 | Tom Mullins | 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 | cc9e9213 | Tom Mullins | |
149 | 18e2028b | Alex | /**
|
150 | * @brief Sets motor speed
|
||
151 | c406f16b | Ben | *
|
152 | * Sets the motor speeds based on subscription to the set_motors topic.
|
||
153 | *
|
||
154 | 18e2028b | Alex | * @param msg The message from the set_motors topic, containing speeds and
|
155 | c406f16b | Ben | * motor configuration settings.
|
156 | */
|
||
157 | 6ebee82c | Alex | void motors_set(const ::messages::set_motors::ConstPtr& msg) |
158 | 18e2028b | Alex | { |
159 | 2814387f | Alex Zirbel | if(msg->fl_set)
|
160 | c9f87aaf | bwasserm | { |
161 | fcd68ec1 | Tom Mullins | motor_fl.set_speed(msg->fl_speed); |
162 | c9f87aaf | bwasserm | } |
163 | 2814387f | Alex Zirbel | if(msg->fr_set)
|
164 | c9f87aaf | bwasserm | { |
165 | fcd68ec1 | Tom Mullins | motor_fr.set_speed(msg->fr_speed); |
166 | c9f87aaf | bwasserm | } |
167 | 2814387f | Alex Zirbel | if(msg->bl_set)
|
168 | c9f87aaf | bwasserm | { |
169 | fcd68ec1 | Tom Mullins | motor_bl.set_speed(msg->bl_speed); |
170 | c9f87aaf | bwasserm | } |
171 | 2814387f | Alex Zirbel | if(msg->br_set)
|
172 | c9f87aaf | bwasserm | { |
173 | fcd68ec1 | Tom Mullins | motor_br.set_speed(msg->br_speed); |
174 | c9f87aaf | bwasserm | } |
175 | |||
176 | 2814387f | Alex Zirbel | ROS_DEBUG("Motor speeds set");
|
177 | c406f16b | Ben | } |
178 | |||
179 | 18e2028b | Alex | /**
|
180 | * @brief Outputs current motor speeds
|
||
181 | c406f16b | Ben | *
|
182 | * Serves the service query_motors by responding to service requests with the
|
||
183 | * speeds of the motors.
|
||
184 | c9f87aaf | bwasserm | * @param req The request. The only field is the units requested.
|
185 | 18e2028b | Alex | * @param res The response. The fields will be filled with values.
|
186 | c406f16b | Ben | */
|
187 | 6ebee82c | Alex | bool motors_query(::messages::query_motors::Request &req,
|
188 | ::messages::query_motors::Response &res) |
||
189 | 18e2028b | Alex | { |
190 | 560d2317 | Tom Mullins | 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 | 18e2028b | Alex | |
195 | ROS_DEBUG("Motor speeds queried");
|
||
196 | a8480867 | Alex Zirbel | |
197 | 18e2028b | Alex | 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 | 9b11c5b3 | Alex Zirbel | */
|
211 | 18e2028b | Alex | 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 | 2814387f | Alex Zirbel | ros::NodeHandle node; |
218 | ros::ServiceServer service = node.advertiseService("query_motors",
|
||
219 | motors_query); |
||
220 | 18e2028b | Alex | |
221 | /* Subscribe to the set_motors topic */
|
||
222 | 2814387f | Alex Zirbel | ros::Subscriber sub0 = node.subscribe("set_motors", QUEUE_SIZE, motors_set);
|
223 | 18e2028b | Alex | |
224 | a8480867 | Alex Zirbel | ROS_INFO("Motors node ready.");
|
225 | 18e2028b | Alex | ros::spin(); |
226 | c406f16b | Ben | |
227 | 18e2028b | Alex | return 0; |
228 | c406f16b | Ben | } |
229 | |||
230 | 9b11c5b3 | Alex Zirbel | /** @} */ |