Revision ce8c3190
ID | ce8c3190b5bdbfd116d77d8feb3c981dcd3cc30e |
Integrated SonarControl into the libscout package.
scout/libscout/src/SonarControl.h | ||
---|---|---|
38 | 38 |
#define _SONAR_CONTROL_H_ |
39 | 39 |
|
40 | 40 |
#include <ros/ros.h> |
41 |
/// @TODO maybe not so good! Then packages have to depend on libscout. |
|
42 |
#include <libscout/constants.h> |
|
43 | 41 |
#include <sonar/sonar_set_scan.h> |
44 | 42 |
#include <sonar/sonar_toggle.h> |
45 | 43 |
#include <sonar/sonar_direction.h> |
... | ... | |
53 | 51 |
/** Sets sonar to a position (0-180 deg) specified by input */ |
54 | 52 |
void set(int position); |
55 | 53 |
|
56 |
/** Sets sonar to scan a range in 0-180 specified by input */
|
|
57 |
void set_range(int start_pos, int end_pos);
|
|
54 |
/** Sets sonar to scan a range in 0-180 specified by input */
|
|
55 |
void set_range(int start_pos, int end_pos);
|
|
58 | 56 |
|
59 | 57 |
/** Returns the distance readings of sonars */ |
60 | 58 |
float query_front(void); |
61 |
float query_back(void);
|
|
59 |
float query_back(void);
|
|
62 | 60 |
|
63 | 61 |
private: |
64 |
/** Converts between values outputted by sensor and physical distances */
|
|
62 |
/** Converts between values output by sensor and physical distances */
|
|
65 | 63 |
float sonar_to_dist(float sonar_value); |
66 | 64 |
float dist_to_sonar(float distance); |
67 | 65 |
|
... | ... | |
71 | 69 |
|
72 | 70 |
/** ROS publisher and client declaration */ |
73 | 71 |
ros::Publisher sonar_set_scan_pub; |
74 |
ros::Publisher sonar_toggle_pub;
|
|
72 |
ros::Publisher sonar_toggle_pub;
|
|
75 | 73 |
ros::ServiceClient query_sonar; |
76 | 74 |
|
77 | 75 |
ros::NodeHandle node; |
78 |
|
|
79 | 76 |
}; |
80 | 77 |
|
81 | 78 |
#endif |
Also available in: Unified diff