scoutos / scout / libscout / src / SonarControl.cpp @ c492be62
History | View | Annotate | Download (5.2 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 |
* Contains functions for the use of sonar control.
|
31 |
*
|
32 |
* @author Colony Project, CMU Robotics Club
|
33 |
* @author Priyanka Deo
|
34 |
* @author Alex Zirbel
|
35 |
**/
|
36 |
|
37 |
#include "SonarControl.h" |
38 |
|
39 |
using namespace std; |
40 |
|
41 |
/**
|
42 |
* @brief Initialize the sonar module of libscout.
|
43 |
*
|
44 |
* Initialize the libscout node as a publisher of sonar_set_scan and
|
45 |
* sonar_toggle and a client of query_sonar.
|
46 |
*/
|
47 |
SonarControl::SonarControl(const ros::NodeHandle& libscout_node,
|
48 |
string scoutname)
|
49 |
: node(libscout_node) |
50 |
{ |
51 |
sonar_set_scan_pub = |
52 |
node.advertise<sonar::sonar_set_scan>(scoutname + "/set_sonar_scan",
|
53 |
QUEUE_SIZE); |
54 |
sonar_toggle_pub = |
55 |
node.advertise<sonar::sonar_toggle>(scoutname + "/toggle_sonar",
|
56 |
QUEUE_SIZE); |
57 |
sonar_distance_sub = node.subscribe(scoutname + "sonar_distance",
|
58 |
QUEUE_SIZE, distance_callback); |
59 |
|
60 |
// Initialize all the sonar readings to 0 and timestamps to undefined
|
61 |
for (int i = 0; i < 48; i++) |
62 |
{ |
63 |
readings[i] = 0;
|
64 |
timestamps[i] = ros::Time::now(); // A common shortcut for no reading
|
65 |
} |
66 |
} |
67 |
|
68 |
/**
|
69 |
* Update the array of sonar values, and the last read timestamps,
|
70 |
* to reflect the new reading received.
|
71 |
*/
|
72 |
void SonarControl::distance_callback(const sonar::sonar_distance::ConstPtr& msg) |
73 |
{ |
74 |
// Error checking so that the array doesn't cause a segfault
|
75 |
if (msg->pos < 0 || msg-> pos > 23) |
76 |
{ |
77 |
ROS_ERROR("SonarControl received an invalid sonar position.");
|
78 |
return;
|
79 |
} |
80 |
|
81 |
readings[msg->pos] = msg->distance0; |
82 |
readings[msg->pos + 24] = msg->distance1;
|
83 |
timestamps[msg->pos] = msg->header.stamp; |
84 |
timestamps[msg->pos + 24] = msg->header.stamp;
|
85 |
} |
86 |
|
87 |
/**
|
88 |
* @brief Sets the sonar to a position.
|
89 |
*
|
90 |
* @param position Value between 0-180 of degree position to set sonar
|
91 |
* @return NONE
|
92 |
* @todo should return bool. See below.
|
93 |
*/
|
94 |
void SonarControl::set_single(int position) |
95 |
{ |
96 |
set_range(position, position); |
97 |
} |
98 |
|
99 |
/**
|
100 |
* @brief Sets the sonar to scan between two positions
|
101 |
*
|
102 |
* @param start_pos The leftmost (smallest) value that the sonar can take
|
103 |
* @param end_pos The rightmost (largest) value that the sonar can take
|
104 |
* @return NONE
|
105 |
* @todo Also misimplemented, should return bool. Look at srv def in sonar/
|
106 |
*/
|
107 |
void SonarControl::set_range(int start_pos, int end_pos) |
108 |
{ |
109 |
// Check that the range is valid
|
110 |
if (start_pos < 0 || end_pos < 0 || start_pos > 23 || end_pos > 23) |
111 |
{ |
112 |
ROS_ERROR("Commanded SonarControl::set_range to a bad value.");
|
113 |
return;
|
114 |
} |
115 |
|
116 |
// Sort the start and end positions into increasing order
|
117 |
if (start_pos > end_pos)
|
118 |
{ |
119 |
int temp = start_pos;
|
120 |
start_pos = end_pos; |
121 |
end_pos = temp; |
122 |
} |
123 |
|
124 |
// Turn sonar on
|
125 |
sonar::sonar_toggle on_msg; |
126 |
on_msg.set_on = true;
|
127 |
sonar_toggle_pub.publish(on_msg); |
128 |
|
129 |
// Set scan range
|
130 |
sonar::sonar_set_scan msg; |
131 |
msg.stop_l = start_pos; |
132 |
msg.stop_r = end_pos; |
133 |
|
134 |
sonar_set_scan_pub.publish(msg); |
135 |
ros::spinOnce(); ///<! Sure? Does this belong here?
|
136 |
} |
137 |
|
138 |
/**
|
139 |
* @brief Turn off sonar readings
|
140 |
*
|
141 |
* Stops sonar from panning and taking readings.
|
142 |
* @todo Misimplemented. Needs to use a service call and return the ack as bool
|
143 |
*
|
144 |
* @return NONE
|
145 |
*/
|
146 |
float SonarControl::set_off()
|
147 |
{ |
148 |
sonar::sonar_toggle on_msg; |
149 |
on_msg.set_on = false;
|
150 |
sonar_toggle_pub.publish(on_msg); |
151 |
} |
152 |
|
153 |
/**
|
154 |
* @brief Converts value returne by sonar to physical distances.
|
155 |
*
|
156 |
* @param sonar_value The returned value of the sonar
|
157 |
* @return The physical distance measured by the sonar.
|
158 |
**/
|
159 |
//float sonar_to_dist(float sonar_value)
|
160 |
//{
|
161 |
//TODO impelement later based on sonar readings
|
162 |
// return sonar_value;
|
163 |
//}
|
164 |
|
165 |
/**
|
166 |
* @brief Converts values from physical distances to values read by sonar
|
167 |
*
|
168 |
* @param distance The physical distance as measured.
|
169 |
* @return The value read by the sonar that corresponds to the given distance
|
170 |
**/
|
171 |
//float dist_to_sonar(float distance)
|
172 |
//{
|
173 |
//TODO implement later based on sonar readings
|
174 |
// return distance;
|
175 |
//}
|