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