Revision b00761a0
ID | b00761a0e88f934a309a939b653d9f441b127ae8 |
Updated ButtonControl and SonarControl.
Finally, the behavior compiles. Had to fix a lot of problems involving misunderstandings with Publisher/Client/ServiceServer/ServiceClient confusion.
We can now run priya_behavior as an executable, though the process for generating behavior executables still needs some work.
scout/libscout/src/SonarControl.h | ||
---|---|---|
40 | 40 |
#include <ros/ros.h> |
41 | 41 |
#include <sonar/sonar_set_scan.h> |
42 | 42 |
#include <sonar/sonar_toggle.h> |
43 |
#include <sonar/sonar_direction.h> |
|
43 |
#include <sonar/sonar_distance.h> |
|
44 |
|
|
45 |
#include "constants.h" |
|
44 | 46 |
|
45 | 47 |
class SonarControl |
46 | 48 |
{ |
... | ... | |
49 | 51 |
SonarControl(const ros::NodeHandle& libscout_node, |
50 | 52 |
std::string scoutname); |
51 | 53 |
|
52 |
/** Sets sonar to a position (0-180 deg) specified by input */
|
|
54 |
/** Sets sonar to a position (0-23) specified by input */
|
|
53 | 55 |
void set_single(int position); |
54 | 56 |
|
55 |
/** Sets sonar to scan a range in 0-180 specified by input */
|
|
57 |
/** Sets sonar to scan a range in 0-23 specified by input */
|
|
56 | 58 |
void set_range(int start_pos, int end_pos); |
57 | 59 |
|
60 |
/** (Re)starts sonar panning and taking readings */ |
|
61 |
void set_on(); |
|
62 |
|
|
58 | 63 |
/** Stops sonar from panning and taking readings */ |
59 | 64 |
void set_off(); |
60 |
|
|
65 |
|
|
61 | 66 |
private: |
62 | 67 |
/** Record the new sonar distance measurement */ |
63 | 68 |
void distance_callback(const sonar::sonar_distance::ConstPtr& msg); |
64 | 69 |
|
70 |
/** Sends a sonar_toggle message. */ |
|
71 |
void set_power(bool is_on); |
|
72 |
|
|
65 | 73 |
/** Converts between values output by sensor and physical distances */ |
66 | 74 |
//float sonar_to_dist(float sonar_value); |
67 | 75 |
//float dist_to_sonar(float distance); |
68 | 76 |
|
77 |
/** If a service call fails, tries again this many times. */ |
|
78 |
int num_attempts; |
|
79 |
|
|
80 |
/** Keep track of the latest readings and their time of receipt. |
|
81 |
* Readings are in millimeters. */ |
|
82 |
int readings[48]; |
|
83 |
ros::Time timestamps[48]; |
|
84 |
|
|
69 | 85 |
/* ROS publisher and client declaration */ |
70 |
ros::Publisher sonar_set_scan_pub;
|
|
71 |
ros::Publisher sonar_toggle_pub;
|
|
86 |
ros::ServiceClient sonar_set_scan_client;
|
|
87 |
ros::ServiceClient sonar_toggle_client;
|
|
72 | 88 |
ros::Subscriber sonar_distance_sub; |
73 | 89 |
|
74 | 90 |
ros::NodeHandle node; |
Also available in: Unified diff