scoutos / scout / libscout / src / SonarControl.cpp @ 7b94db2c
History | View | Annotate | Download (6.28 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 SonarControl.cpp
|
28 |
* @brief Contains sonar function implementation
|
29 |
*
|
30 |
* @defgroup sonarcontrol SonarControl
|
31 |
* @brief Functions which a behavior can use to control the sonar.
|
32 |
* @ingroup behavior
|
33 |
*
|
34 |
* @author Colony Project, CMU Robotics Club
|
35 |
* @author Priyanka Deo
|
36 |
* @author Alex Zirbel
|
37 |
*
|
38 |
* @{
|
39 |
**/
|
40 |
|
41 |
#include "SonarControl.h" |
42 |
|
43 |
#define MAX_ATTEMPTS 10 |
44 |
|
45 |
using namespace std; |
46 |
|
47 |
/**
|
48 |
* @brief Initialize the sonar module of libscout.
|
49 |
*
|
50 |
* Initialize the libscout node as a publisher of sonar_set_scan and
|
51 |
* sonar_toggle and a client of query_sonar.
|
52 |
*/
|
53 |
SonarControl::SonarControl(const ros::NodeHandle& libscout_node,
|
54 |
string scoutname)
|
55 |
: node(libscout_node) |
56 |
{ |
57 |
sonar_set_scan_client = |
58 |
node.serviceClient< ::messages::sonar_set_scan>(scoutname+"/set_sonar_scan");
|
59 |
sonar_toggle_client = |
60 |
node.serviceClient< ::messages::sonar_toggle>(scoutname + "/toggle_sonar");
|
61 |
sonar_distance_sub = node.subscribe(scoutname + "/sonar_distance",
|
62 |
QUEUE_SIZE, |
63 |
&SonarControl::distance_callback, |
64 |
this);
|
65 |
|
66 |
// Initialize all the sonar readings to 0 and timestamps to undefined
|
67 |
for (int i = 0; i < 48; i++) |
68 |
{ |
69 |
readings[i] = 0;
|
70 |
timestamps[i] = ros::Time::now(); // A common shortcut for no reading
|
71 |
} |
72 |
|
73 |
ROS_INFO("Readings at 0, ready to go.");
|
74 |
|
75 |
/// @todo Test, and replace 10 with a const int
|
76 |
num_attempts = MAX_ATTEMPTS; |
77 |
} |
78 |
|
79 |
/**
|
80 |
* Update the array of sonar values, and the last read timestamps,
|
81 |
* to reflect the new reading received.
|
82 |
*/
|
83 |
void SonarControl::distance_callback(const ::messages::sonar_distance::ConstPtr& msg) |
84 |
{ |
85 |
// Error checking so that the array doesn't cause a segfault
|
86 |
if (msg->pos < 0 || msg-> pos > 23) |
87 |
{ |
88 |
ROS_ERROR("SonarControl received an invalid sonar position.");
|
89 |
return;
|
90 |
} |
91 |
|
92 |
readings[msg->pos] = msg->distance0; |
93 |
readings[msg->pos + 24] = msg->distance1;
|
94 |
|
95 |
timestamps[msg->pos] = msg->stamp; |
96 |
timestamps[msg->pos + 24] = msg->stamp;
|
97 |
|
98 |
|
99 |
} |
100 |
|
101 |
/**
|
102 |
* @brief Sets the sonar to a position.
|
103 |
*
|
104 |
* @param position Value between 0-180 of degree position to set sonar
|
105 |
*/
|
106 |
void SonarControl::set_single(int position) |
107 |
{ |
108 |
set_range(position, position); |
109 |
} |
110 |
|
111 |
/**
|
112 |
* @brief Sets the sonar to scan between two positions
|
113 |
*
|
114 |
* @param start_pos The leftmost (smallest) value that the sonar can take
|
115 |
* @param end_pos The rightmost (largest) value that the sonar can take
|
116 |
*/
|
117 |
void SonarControl::set_range(int start_pos, int end_pos) |
118 |
{ |
119 |
// Check that the range is valid
|
120 |
if (start_pos < 0 || end_pos < 0 || start_pos > 23 || end_pos > 23) |
121 |
{ |
122 |
ROS_ERROR("Commanded SonarControl::set_range to a bad value.");
|
123 |
return;
|
124 |
} |
125 |
|
126 |
// Sort the start and end positions into increasing order
|
127 |
if (start_pos > end_pos)
|
128 |
{ |
129 |
int temp = start_pos;
|
130 |
start_pos = end_pos; |
131 |
end_pos = temp; |
132 |
} |
133 |
|
134 |
// Make sure sonar is on
|
135 |
set_on(); |
136 |
|
137 |
// Set scan range
|
138 |
::messages::sonar_set_scan srv; |
139 |
srv.request.stop_l = start_pos; |
140 |
srv.request.stop_r = end_pos; |
141 |
|
142 |
// Check if the service call failed or if the response was false
|
143 |
if (!sonar_set_scan_client.call(srv) || srv.response.ack == false) |
144 |
{ |
145 |
if (--num_attempts == 0) |
146 |
{ |
147 |
ROS_ERROR("SonarControl::set_range() failed permanently.");
|
148 |
} |
149 |
|
150 |
ROS_WARN("SonarControl::set_range() failed once.");
|
151 |
} |
152 |
} |
153 |
|
154 |
/**
|
155 |
* @brief Turn on sonar readings
|
156 |
*
|
157 |
* (Re)starts sonar panning and taking readings.
|
158 |
*/
|
159 |
void SonarControl::set_on()
|
160 |
{ |
161 |
set_power(true);
|
162 |
} |
163 |
|
164 |
/**
|
165 |
* @brief Turn off sonar readings
|
166 |
*
|
167 |
* Stops sonar from panning and taking readings.
|
168 |
*/
|
169 |
void SonarControl::set_off()
|
170 |
{ |
171 |
set_power(false);
|
172 |
} |
173 |
|
174 |
/**
|
175 |
* @brief Turn sonar readings either off or on.
|
176 |
*
|
177 |
* Attempts to turn the readings off or on, num_attempts times.
|
178 |
*
|
179 |
* @param is_on True if power should be set on, false if should be off.
|
180 |
*/
|
181 |
void SonarControl::set_power(bool is_on) |
182 |
{ |
183 |
::messages::sonar_toggle srv; |
184 |
srv.request.set_on = is_on; |
185 |
|
186 |
// Check if the service call failed or if the response was false
|
187 |
if (!sonar_toggle_client.call(srv) || srv.response.ack == false) |
188 |
{ |
189 |
if (--num_attempts == 0) |
190 |
{ |
191 |
ROS_ERROR("SonarControl::set_power() failed permanently.");
|
192 |
} |
193 |
|
194 |
ROS_WARN("SonarControl::set_power() failed once.");
|
195 |
} |
196 |
ROS_INFO("SonarControl::set_power() succeeded.");
|
197 |
|
198 |
// Reset num_attempts
|
199 |
num_attempts = MAX_ATTEMPTS; |
200 |
} |
201 |
|
202 |
int* SonarControl::get_sonar_readings()
|
203 |
{ |
204 |
return readings;
|
205 |
} |
206 |
|
207 |
/**
|
208 |
* @brief Converts value returne by sonar to physical distances.
|
209 |
*
|
210 |
* @param sonar_value The returned value of the sonar
|
211 |
* @return The physical distance measured by the sonar.
|
212 |
**/
|
213 |
//float sonar_to_dist(float sonar_value)
|
214 |
//{
|
215 |
//@todo impelement later based on sonar readings
|
216 |
// return sonar_value;
|
217 |
//}
|
218 |
|
219 |
/**
|
220 |
* @brief Converts values from physical distances to values read by sonar
|
221 |
*
|
222 |
* @param distance The physical distance as measured.
|
223 |
* @return The value read by the sonar that corresponds to the given distance
|
224 |
**/
|
225 |
//float dist_to_sonar(float distance)
|
226 |
//{
|
227 |
//@todo implement later based on sonar readings
|
228 |
// return distance;
|
229 |
//}
|
230 |
|
231 |
/** @} */
|