root / scout / motors / src / motors.cpp @ 3a73516c
History | View | Annotate | Download (5.78 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 |
* @defgroup motors Motors
|
31 |
* @brief Functions for using the motors
|
32 |
*
|
33 |
* @author Colony Project, CMU Robotics Club
|
34 |
* @author Ben Wasserman
|
35 |
* @author Tom Mullins
|
36 |
*
|
37 |
* @{
|
38 |
*/
|
39 |
|
40 |
#include <ros/ros.h> |
41 |
#include <cstdlib> |
42 |
#include "motors.h" |
43 |
|
44 |
using namespace std; |
45 |
|
46 |
/**
|
47 |
* @brief Motor constructor
|
48 |
*
|
49 |
* Opens device file and reads initial PWM value
|
50 |
*
|
51 |
* @param filename The name of the PWM device file
|
52 |
*/
|
53 |
Motor::Motor(int pwm_gpt, int in1_gpio, int in2_gpio) |
54 |
{ |
55 |
char buf[60]; |
56 |
|
57 |
// open device files
|
58 |
sprintf(buf, "/dev/pwm%d", pwm_gpt);
|
59 |
fpwm.open(buf, ios::out); |
60 |
sprintf(buf, "/sys/class/gpio/gpio%d/value", in1_gpio);
|
61 |
fin1.open(buf, ios::out); |
62 |
sprintf(buf, "/sys/class/gpio/gpio%d/value", in2_gpio);
|
63 |
fin2.open(buf, ios::out); |
64 |
|
65 |
/* I set speed to 0 here rather than reading in what the current speed is
|
66 |
* because the pwm driver does not support seeking in the device files.
|
67 |
* Doing both reading and writing causes fpwm to attempt seeking, which
|
68 |
* fails, causing fpwm to refuse to do any more io. So, we can only write.
|
69 |
*/
|
70 |
speed = 0;
|
71 |
|
72 |
// ensure we are in a consistent state by writing to hardware
|
73 |
set_speed(speed); |
74 |
} |
75 |
|
76 |
/**
|
77 |
* @brief Motor destructor
|
78 |
*
|
79 |
* Sets the motor's speed to zero in preparation for the node exiting
|
80 |
*/
|
81 |
Motor::~Motor() |
82 |
{ |
83 |
set_speed(0);
|
84 |
} |
85 |
|
86 |
/**
|
87 |
* @brief Returns current motor speed
|
88 |
*
|
89 |
* Note that this doesn't read from the hardware
|
90 |
*/
|
91 |
int Motor::get_speed()
|
92 |
{ |
93 |
return speed;
|
94 |
} |
95 |
|
96 |
/**
|
97 |
* @brief Sets motor speed
|
98 |
*
|
99 |
* This will set the member this->speed and write the new speed to the hardware
|
100 |
*
|
101 |
* @param new_speed The speed to set, between +/- MAXSPEED inclusive
|
102 |
*/
|
103 |
void Motor::set_speed(int new_speed) |
104 |
{ |
105 |
int pwm, in1, in2;
|
106 |
|
107 |
speed = new_speed; |
108 |
|
109 |
// convert to hardware units
|
110 |
if (speed == 0) |
111 |
{ |
112 |
/// @todo should this be off (00) or short brake (11)?
|
113 |
pwm = 0;
|
114 |
in1 = 0;
|
115 |
in2 = 0;
|
116 |
} |
117 |
else if (speed > 0) |
118 |
{ |
119 |
// CW
|
120 |
pwm = speed; |
121 |
in1 = 1;
|
122 |
in2 = 0;
|
123 |
} |
124 |
else
|
125 |
{ |
126 |
// CCW
|
127 |
pwm = -speed; |
128 |
in1 = 0;
|
129 |
in2 = 1;
|
130 |
} |
131 |
|
132 |
// write to hardware
|
133 |
fpwm << pwm << flush; |
134 |
fin1 << in1 << flush; |
135 |
fin2 << in2 << flush; |
136 |
} |
137 |
|
138 |
/// @todo change these to the correct motor locations / directions
|
139 |
// Motor state variables
|
140 |
static Motor motor_fl( 8, 70, 71); |
141 |
static Motor motor_fr( 9, 72, 73); |
142 |
static Motor motor_bl(11, 74, 75); |
143 |
static Motor motor_br(10, 76, 77); |
144 |
|
145 |
/**
|
146 |
* @brief Sets motor speed
|
147 |
*
|
148 |
* Sets the motor speeds based on subscription to the set_motors topic.
|
149 |
*
|
150 |
* @param msg The message from the set_motors topic, containing speeds and
|
151 |
* motor configuration settings.
|
152 |
*/
|
153 |
void motors_set(const ::messages::set_motors::ConstPtr& msg) |
154 |
{ |
155 |
if(msg->fl_set)
|
156 |
{ |
157 |
motor_fl.set_speed(msg->fl_speed); |
158 |
} |
159 |
if(msg->fr_set)
|
160 |
{ |
161 |
motor_fr.set_speed(msg->fr_speed); |
162 |
} |
163 |
if(msg->bl_set)
|
164 |
{ |
165 |
motor_bl.set_speed(msg->bl_speed); |
166 |
} |
167 |
if(msg->br_set)
|
168 |
{ |
169 |
motor_br.set_speed(msg->br_speed); |
170 |
} |
171 |
|
172 |
ROS_DEBUG("Motor speeds set");
|
173 |
} |
174 |
|
175 |
/**
|
176 |
* @brief Outputs current motor speeds
|
177 |
*
|
178 |
* Serves the service query_motors by responding to service requests with the
|
179 |
* speeds of the motors.
|
180 |
* @param req The request. The only field is the units requested.
|
181 |
* @param res The response. The fields will be filled with values.
|
182 |
*/
|
183 |
bool motors_query(::messages::query_motors::Request &req,
|
184 |
::messages::query_motors::Response &res) |
185 |
{ |
186 |
res.fl_speed = motor_fl.get_speed(); |
187 |
res.fr_speed = motor_fr.get_speed(); |
188 |
res.bl_speed = motor_bl.get_speed(); |
189 |
res.br_speed = motor_br.get_speed(); |
190 |
|
191 |
ROS_DEBUG("Motor speeds queried");
|
192 |
|
193 |
return true; |
194 |
} |
195 |
|
196 |
/**
|
197 |
* @brief Motors driver. This is a ROS node that controls motor speeds.
|
198 |
*
|
199 |
* This is the main function for the motors node. It is run when the node
|
200 |
* starts and initializes the motors. It then subscribes to the
|
201 |
* set_motors, and set_motor_speeds topics, and advertises the
|
202 |
* query_motors service.
|
203 |
*
|
204 |
* @param argc The number of command line arguments (should be 1)
|
205 |
* @param argv The array of command line arguments
|
206 |
*/
|
207 |
int main(int argc, char **argv) |
208 |
{ |
209 |
/* Initialize in ROS the motors driver node */
|
210 |
ros::init(argc, argv, "motors_driver");
|
211 |
|
212 |
/* Advertise that this serves the query_motors service */
|
213 |
ros::NodeHandle node; |
214 |
ros::ServiceServer service = node.advertiseService("query_motors",
|
215 |
motors_query); |
216 |
|
217 |
/* Subscribe to the set_motors topic */
|
218 |
ros::Subscriber sub0 = node.subscribe("set_motors", QUEUE_SIZE, motors_set);
|
219 |
|
220 |
ROS_INFO("Motors node ready.");
|
221 |
ros::spin(); |
222 |
|
223 |
return 0; |
224 |
} |
225 |
|
226 |
/** @} */
|