#include "ros/ros.h"
#include "sensor_msgs/Range.h"
#include <diagnostic_updater/diagnostic_updater.h>
#include <diagnostic_updater/publisher.h>
#include <dynamic_reconfigure/server.h>
#include <evarobot_sonar/SonarParamsConfig.h>
#include <time.h>
#include <vector>
#include <sstream>
#include <stdio.h>
#include <stdlib.h>
#include <fcntl.h>
#include <math.h>
#include <unistd.h>
#include <sys/ioctl.h>
#include <exception>
#include <boost/shared_ptr.hpp>
#include <ros/console.h>
#include "ErrorCodes.h"
Go to the source code of this file.
Classes | |
class | IMDynamicReconfig |
class | IMSONAR |
struct | sonar_data |
struct | sonar_ioc_transfer |
Defines | |
#define | IOCTL_READ_RANGE _IOWR(SNRDRIVER_IOCTL_BASE, 1, struct sonar_data) |
#define | IOCTL_SET_PARAM _IOW(SNRDRIVER_IOCTL_BASE, 0, struct sonar_ioc_transfer) |
#define | MAX_SONAR 7 |
#define | MAX_TRIGGER_TIME 1.2 |
#define | SNRDRIVER_IOCTL_BASE 0xAE |
Variables | |
bool | b_is_received_params = false |
bool | g_b_always_on |
double | g_d_field_of_view |
double | g_d_max_range |
double | g_d_min_range |
int | g_i_is_alive [MAX_SONAR] |
int | SONAR [] = {23, 24, 25, 26, 16, 20, 21} |
#define IOCTL_READ_RANGE _IOWR(SNRDRIVER_IOCTL_BASE, 1, struct sonar_data) |
Definition at line 55 of file evarobot_sonar.h.
#define IOCTL_SET_PARAM _IOW(SNRDRIVER_IOCTL_BASE, 0, struct sonar_ioc_transfer) |
Definition at line 53 of file evarobot_sonar.h.
#define MAX_SONAR 7 |
Definition at line 36 of file evarobot_sonar.h.
#define MAX_TRIGGER_TIME 1.2 |
Definition at line 35 of file evarobot_sonar.h.
#define SNRDRIVER_IOCTL_BASE 0xAE |
Definition at line 50 of file evarobot_sonar.h.
bool b_is_received_params = false |
Definition at line 59 of file evarobot_sonar.h.
bool g_b_always_on |
Definition at line 64 of file evarobot_sonar.h.
double g_d_field_of_view |
Definition at line 61 of file evarobot_sonar.h.
double g_d_max_range |
Definition at line 63 of file evarobot_sonar.h.
double g_d_min_range |
Definition at line 62 of file evarobot_sonar.h.
int g_i_is_alive[MAX_SONAR] |
Definition at line 66 of file evarobot_sonar.h.
int SONAR[] = {23, 24, 25, 26, 16, 20, 21} |
Definition at line 58 of file evarobot_sonar.h.