scoutos / scout / cliffsensor / src / cliffsensor.cpp @ 04f50f8a
History | View | Annotate | Download (6.67 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 cliffsensor.cpp
|
28 |
* @brief Contains code to control the cliffsensor.
|
29 |
*
|
30 |
* Implementation of functions for cliffsensor use.
|
31 |
*
|
32 |
* @author Colony Project, CMU Robotics Club
|
33 |
* @author Priyanka Deo
|
34 |
**/
|
35 |
|
36 |
#include "ros/ros.h" |
37 |
#include "cliffsensor.h" |
38 |
#include <cstdlib> |
39 |
|
40 |
/**
|
41 |
* @defgroup cliffsensor Cliffsensor
|
42 |
* @brief Functions for using the cliffsensors
|
43 |
*
|
44 |
* @{
|
45 |
**/
|
46 |
|
47 |
/* Cliffsensor state variables
|
48 |
*/
|
49 |
static int front_raw; /**< The current raw value data of the front cliffsensor. */ |
50 |
static int left_raw; /**< The current raw value data of the left cliffsensor. */ |
51 |
static int back_raw; /**< The current raw value data of the right cliffsensor. */ |
52 |
static bool is_cliff; /**< Boolean to represent whether or not there is a cliff. */ |
53 |
|
54 |
/**
|
55 |
* @brief Sets motor speed
|
56 |
*
|
57 |
* Sets the motor speeds based on subscription to the set_motors topic.
|
58 |
*
|
59 |
* @param msg The message from the set_motors topic, containing speeds and
|
60 |
* motor configuration settings.
|
61 |
*/
|
62 |
void motors_set(const motors::set_motors::ConstPtr& msg) |
63 |
{ |
64 |
/** @todo Edit to only set requested motors, not all */
|
65 |
int which = msg->which;
|
66 |
if(which & MOTOR_FL_REV)
|
67 |
{ |
68 |
motor_fl_speed = -1 * motors_rel_to_abs(msg->fl_speed, msg->units);
|
69 |
} |
70 |
if(which & MOTOR_FR_REV)
|
71 |
{ |
72 |
motor_fr_speed = -1 * motors_rel_to_abs(msg->fr_speed, msg->units);
|
73 |
} |
74 |
if(which & MOTOR_BL_REV)
|
75 |
{ |
76 |
motor_bl_speed = -1 * motors_rel_to_abs(msg->bl_speed, msg->units);
|
77 |
} |
78 |
if(which & MOTOR_BR_REV)
|
79 |
{ |
80 |
motor_br_speed = -1 * motors_rel_to_abs(msg->br_speed, msg->units);
|
81 |
} |
82 |
if(which & MOTOR_FL)
|
83 |
{ |
84 |
motor_fl_speed = motors_rel_to_abs(msg->fl_speed, msg->units); |
85 |
} |
86 |
if(which & MOTOR_FR)
|
87 |
{ |
88 |
motor_fr_speed = motors_rel_to_abs(msg->fr_speed, msg->units); |
89 |
} |
90 |
if(which & MOTOR_BL)
|
91 |
{ |
92 |
motor_bl_speed = motors_rel_to_abs(msg->bl_speed, msg->units); |
93 |
} |
94 |
if(which & MOTOR_BR)
|
95 |
{ |
96 |
motor_br_speed = motors_rel_to_abs(msg->br_speed, msg->units); |
97 |
} |
98 |
|
99 |
/* Write speeds to hardware */
|
100 |
/** @todo Add code to write speeds to hardware */
|
101 |
} |
102 |
|
103 |
/**
|
104 |
* @brief Outputs current motor speeds
|
105 |
*
|
106 |
* Serves the service query_motors by responding to service requests with the
|
107 |
* speeds of the motors.
|
108 |
* @param req The request. The only field is the units requested.
|
109 |
* @param res The response. The fields will be filled with values.
|
110 |
*/
|
111 |
bool motors_query(motors::query_motors::Request &req,
|
112 |
motors::query_motors::Response &res) |
113 |
{ |
114 |
int units = req.units;
|
115 |
res.fl_speed = motors_abs_to_rel(motor_fl_speed, units); |
116 |
res.fr_speed = motors_abs_to_rel(motor_fr_speed, units); |
117 |
res.bl_speed = motors_abs_to_rel(motor_bl_speed, units); |
118 |
res.br_speed = motors_abs_to_rel(motor_br_speed, units); |
119 |
|
120 |
ROS_DEBUG("Motor speeds queried");
|
121 |
return true; |
122 |
} |
123 |
|
124 |
/**
|
125 |
* @brief Converts set speeds (of various units) to absolute speeds.
|
126 |
*
|
127 |
* @param speed The speed expressed in the desired units
|
128 |
* @param units The units the desired speed is measured in
|
129 |
* @return The absolute speed of the motor
|
130 |
**/
|
131 |
int motors_rel_to_abs(int rel_speed, int units) |
132 |
{ |
133 |
switch(units)
|
134 |
{ |
135 |
case MOTOR_ABSOLUTE:/* Speed given as absolute */ |
136 |
return rel_speed;
|
137 |
case MOTOR_PERCENT:/* Convert from percentage */ |
138 |
return rel_speed * MAXSPEED / 100; |
139 |
case MOTOR_MMS:/* Convert from mm/s */ |
140 |
/** @todo Make math to do this conversion **/
|
141 |
return rel_speed;
|
142 |
case MOTOR_CMS:/* Convert from cm/s */ |
143 |
/** @todo Make math to do this conversion **/
|
144 |
return rel_speed;
|
145 |
default: /* The units aren't recognized */ |
146 |
/** @todo Decide on default case. Either percent or absolute. **/
|
147 |
return rel_speed;
|
148 |
} |
149 |
} |
150 |
|
151 |
/**
|
152 |
* @brief Convert absolute speeds to speeds of various units.
|
153 |
*
|
154 |
* @param speed The speed expressed in absolute units.
|
155 |
* @param units The units the desired speed is measured in.
|
156 |
* @return The relative speed of the motor in desired units.
|
157 |
**/
|
158 |
int motors_abs_to_rel(int abs_speed, int units) |
159 |
{ |
160 |
switch(units)
|
161 |
{ |
162 |
case MOTOR_ABSOLUTE:/* Speed given as absolute */ |
163 |
return abs_speed;
|
164 |
case MOTOR_PERCENT:/* Convert from percentage */ |
165 |
return abs_speed * 100 / MAXSPEED; |
166 |
case MOTOR_MMS:/* Convert from mm/s */ |
167 |
/** @todo Make math to do this conversion **/
|
168 |
return abs_speed;
|
169 |
case MOTOR_CMS:/* Convert from cm/s */ |
170 |
/** @todo Make math to do this conversion **/
|
171 |
return abs_speed;
|
172 |
default: /* The units aren't recognized */ |
173 |
/** @todo Decide on default case. Either percent or absolute. **/
|
174 |
return abs_speed;
|
175 |
} |
176 |
} |
177 |
|
178 |
/**
|
179 |
* @brief Motors driver. This is a ROS node that controls motor speeds.
|
180 |
*
|
181 |
* This is the main function for the motors node. It is run when the node
|
182 |
* starts and initializes the motors. It then subscribes to the
|
183 |
* set_motors, and set_motor_speeds topics, and advertises the
|
184 |
* query_motors service.
|
185 |
*
|
186 |
* @param argc The number of command line arguments (should be 1)
|
187 |
* @param argv The array of command line arguments
|
188 |
**/
|
189 |
int main(int argc, char **argv) |
190 |
{ |
191 |
/* Initialize in ROS the motors driver node */
|
192 |
ros::init(argc, argv, "motors_driver");
|
193 |
|
194 |
/* Advertise that this serves the query_motors service */
|
195 |
ros::NodeHandle n; |
196 |
ros::ServiceServer service = n.advertiseService("query_motors",
|
197 |
motors_query); |
198 |
|
199 |
/* Subscribe to the set_motors topic */
|
200 |
ros::Subscriber sub0 = n.subscribe("set_motors", 4, motors_set); |
201 |
|
202 |
/* Initialize hardware for motors */
|
203 |
// Hardware init functions here
|
204 |
|
205 |
ROS_INFO("Ready to set motors.");
|
206 |
ros::spin(); |
207 |
|
208 |
return 0; |
209 |
} |
210 |
|
211 |
/** @} **/
|