#include <evarobot_sonar.h>
Public Member Functions | |
| bool | Check () |
| int | Echo () |
| IMSONAR (int fd, int id, int pin, boost::shared_ptr< IMDynamicReconfig > _dynamic_params) | |
| void | ProduceDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| void | Publish () |
| void | Trigger () |
| void | Wait () |
| ~IMSONAR () | |
Public Attributes | |
| ros::NodeHandle | n |
| ros::Publisher | pub_sonar |
| diagnostic_updater::Updater | updater |
Private Attributes | |
| bool | b_is_alive |
| struct sonar_data | data |
| boost::shared_ptr < IMDynamicReconfig > | dynamic_params |
| int | i_fd |
| int | i_id |
| int | i_pin_no |
| double | max_freq |
| double | min_freq |
| diagnostic_updater::HeaderlessTopicDiagnostic * | pub_sonar_freq |
| sensor_msgs::Range | sonar_msg |
Definition at line 87 of file evarobot_sonar.h.
| IMSONAR::IMSONAR | ( | int | fd, |
| int | id, | ||
| int | pin, | ||
| boost::shared_ptr< IMDynamicReconfig > | _dynamic_params | ||
| ) |
Definition at line 12 of file evarobot_sonar.cpp.
Definition at line 48 of file evarobot_sonar.cpp.
| bool IMSONAR::Check | ( | ) |
Definition at line 53 of file evarobot_sonar.cpp.
| int IMSONAR::Echo | ( | ) |
Definition at line 107 of file evarobot_sonar.cpp.
Definition at line 144 of file evarobot_sonar.cpp.
| void IMSONAR::Publish | ( | ) |
Definition at line 135 of file evarobot_sonar.cpp.
| void IMSONAR::Trigger | ( | ) |
Definition at line 97 of file evarobot_sonar.cpp.
| void IMSONAR::Wait | ( | ) |
Definition at line 130 of file evarobot_sonar.cpp.
bool IMSONAR::b_is_alive [private] |
Definition at line 111 of file evarobot_sonar.h.
struct sonar_data IMSONAR::data [private] |
Definition at line 122 of file evarobot_sonar.h.
boost::shared_ptr<IMDynamicReconfig> IMSONAR::dynamic_params [private] |
Definition at line 115 of file evarobot_sonar.h.
int IMSONAR::i_fd [private] |
Definition at line 109 of file evarobot_sonar.h.
int IMSONAR::i_id [private] |
Definition at line 110 of file evarobot_sonar.h.
int IMSONAR::i_pin_no [private] |
Definition at line 110 of file evarobot_sonar.h.
double IMSONAR::max_freq [private] |
Definition at line 118 of file evarobot_sonar.h.
double IMSONAR::min_freq [private] |
Definition at line 117 of file evarobot_sonar.h.
Definition at line 104 of file evarobot_sonar.h.
Definition at line 105 of file evarobot_sonar.h.
Definition at line 119 of file evarobot_sonar.h.
sensor_msgs::Range IMSONAR::sonar_msg [private] |
Definition at line 113 of file evarobot_sonar.h.
Definition at line 106 of file evarobot_sonar.h.