root / scout / motors / src / motors.cpp @ cc9e9213
History | View | Annotate | Download (5.24 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 |
*/
|
35 |
|
36 |
#include <ros/ros.h> |
37 |
#include <cstdlib> |
38 |
#include <fstream> |
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 |
/* Motor state variables
|
51 |
* Speeds expressed as absolute speed out of max speed (0 - +-MAXSPEED)
|
52 |
* Absolute speed is the speed written to the hardware to move the motors
|
53 |
*/
|
54 |
static int motor_fl_speed; /**< The current speed of the front left motor. */ |
55 |
static int motor_fr_speed; /**< The current speed of the front right motor. */ |
56 |
static int motor_bl_speed; /**< The current speed of the back left motor. */ |
57 |
static int motor_br_speed; /**< The current speed of the back right motor. */ |
58 |
|
59 |
static fstream motor_fl_file; /**< The device file for the front left motor. */ |
60 |
static fstream motor_fr_file; /**< The device file for the front right motor. */ |
61 |
static fstream motor_bl_file; /**< The device file for the back left motor. */ |
62 |
static fstream motor_br_file; /**< The device file for the back right motor. */ |
63 |
|
64 |
/**
|
65 |
* @brief Sets motor speed
|
66 |
*
|
67 |
* Sets the motor speeds based on subscription to the set_motors topic.
|
68 |
*
|
69 |
* @param msg The message from the set_motors topic, containing speeds and
|
70 |
* motor configuration settings.
|
71 |
*/
|
72 |
void motors_set(const motors::set_motors::ConstPtr& msg) |
73 |
{ |
74 |
if(msg->fl_set)
|
75 |
{ |
76 |
motor_fl_speed = msg->fl_speed; |
77 |
motor_fl_file << motor_fl_speed; |
78 |
} |
79 |
if(msg->fr_set)
|
80 |
{ |
81 |
motor_fr_speed = msg->fr_speed; |
82 |
motor_fr_file << motor_fr_speed; |
83 |
} |
84 |
if(msg->bl_set)
|
85 |
{ |
86 |
motor_bl_speed = msg->bl_speed; |
87 |
motor_bl_file << motor_bl_speed; |
88 |
} |
89 |
if(msg->br_set)
|
90 |
{ |
91 |
motor_br_speed = msg->br_speed; |
92 |
motor_br_file << motor_br_speed; |
93 |
} |
94 |
|
95 |
ROS_DEBUG("Motor speeds set");
|
96 |
} |
97 |
|
98 |
/**
|
99 |
* @brief Outputs current motor speeds
|
100 |
*
|
101 |
* Serves the service query_motors by responding to service requests with the
|
102 |
* speeds of the motors.
|
103 |
* @param req The request. The only field is the units requested.
|
104 |
* @param res The response. The fields will be filled with values.
|
105 |
*/
|
106 |
bool motors_query(motors::query_motors::Request &req,
|
107 |
motors::query_motors::Response &res) |
108 |
{ |
109 |
/** @todo Are we checking hardware or just using the saved values?
|
110 |
* Saved values sound fine to me (Alex). Pleas confirm.
|
111 |
* I think saved values are ok; they're read in from hardware at the
|
112 |
* beginning (Tom). */
|
113 |
res.fl_speed = motor_fl_speed; |
114 |
res.fr_speed = motor_fr_speed; |
115 |
res.bl_speed = motor_bl_speed; |
116 |
res.br_speed = motor_br_speed; |
117 |
|
118 |
ROS_DEBUG("Motor speeds queried");
|
119 |
|
120 |
return true; |
121 |
} |
122 |
|
123 |
/**
|
124 |
* @brief Motors driver. This is a ROS node that controls motor speeds.
|
125 |
*
|
126 |
* This is the main function for the motors node. It is run when the node
|
127 |
* starts and initializes the motors. It then subscribes to the
|
128 |
* set_motors, and set_motor_speeds topics, and advertises the
|
129 |
* query_motors service.
|
130 |
*
|
131 |
* @param argc The number of command line arguments (should be 1)
|
132 |
* @param argv The array of command line arguments
|
133 |
*/
|
134 |
int main(int argc, char **argv) |
135 |
{ |
136 |
/* Initialize in ROS the motors driver node */
|
137 |
ros::init(argc, argv, "motors_driver");
|
138 |
|
139 |
/* Advertise that this serves the query_motors service */
|
140 |
ros::NodeHandle node; |
141 |
ros::ServiceServer service = node.advertiseService("query_motors",
|
142 |
motors_query); |
143 |
|
144 |
/* Subscribe to the set_motors topic */
|
145 |
ros::Subscriber sub0 = node.subscribe("set_motors", QUEUE_SIZE, motors_set);
|
146 |
|
147 |
/* Open device files for PWM values */
|
148 |
/** @todo These are probably not the correct order */
|
149 |
motor_fl_file.open("/dev/pwm8");
|
150 |
motor_fr_file.open("/dev/pwm9");
|
151 |
motor_bl_file.open("/dev/pwm10");
|
152 |
motor_br_file.open("/dev/pwm11");
|
153 |
|
154 |
/* Get initial values, for motor queries */
|
155 |
motor_fl_file >> motor_fl_speed; |
156 |
motor_fr_file >> motor_fr_speed; |
157 |
motor_bl_file >> motor_bl_speed; |
158 |
motor_br_file >> motor_br_speed; |
159 |
|
160 |
ROS_INFO("Motors node ready.");
|
161 |
ros::spin(); |
162 |
|
163 |
return 0; |
164 |
} |
165 |
|
166 |
/** @} */
|