os32c.h
Go to the documentation of this file.
1 
26 #ifndef OMRON_OS32C_DRIVER_OS32C_H
27 #define OMRON_OS32C_DRIVER_OS32C_H
28 
29 #include <gtest/gtest_prod.h>
30 #include <string>
31 #include <vector>
32 #include <boost/shared_ptr.hpp>
33 #include <sensor_msgs/LaserScan.h>
34 
40 
41 using std::vector;
42 using boost::shared_ptr;
43 using sensor_msgs::LaserScan;
44 using eip::Session;
46 
47 #define DEG2RAD(a) (a * M_PI / 180)
48 #define RAD2DEG(a) (a * 180 / M_PI)
49 
50 namespace omron_os32c_driver {
51 
52 
53 typedef enum
54 {
62 
63 typedef enum
64 {
69 
75 class OS32C : public Session
76 {
77 public:
83  : Session(socket, io_socket)
86  , connection_num_(-1)
88  {
89  }
90 
91  static const double ANGLE_MIN;
92  static const double ANGLE_MAX;
93  static const double ANGLE_INC;
94  static const double DISTANCE_MIN;
95  static const double DISTANCE_MAX;
96 
104 
111  void setRangeFormat(EIP_UINT format);
112 
120 
127  void setReflectivityFormat(EIP_UINT format);
128 
129 
137  void selectBeams(double start_angle, double end_angle);
138 
145 
157  static inline int calcBeamNumber(double angle)
158  {
159  return (ANGLE_MAX - angle + ANGLE_INC / 2) / ANGLE_INC;
160  }
161 
168  static inline double calcBeamCentre(int beam_num)
169  {
170  return ANGLE_MAX - beam_num * ANGLE_INC;
171  }
172 
178  void fillLaserScanStaticConfig(sensor_msgs::LaserScan* ls);
179 
187  static void convertToLaserScan(const RangeAndReflectanceMeasurement& rr, sensor_msgs::LaserScan* ls);
188 
194  static void convertToLaserScan(const MeasurementReport& mr, sensor_msgs::LaserScan* ls);
195 
197 
199 
200  void startUDPIO();
201 
202  void closeActiveConnection();
203 
204 private:
205  // allow unit tests to access the helpers below for direct testing
206  FRIEND_TEST(OS32CTest, test_calc_beam_mask_all);
207  FRIEND_TEST(OS32CTest, test_calc_beam_at_90);
208  FRIEND_TEST(OS32CTest, test_calc_beam_boundaries);
209  FRIEND_TEST(OS32CTest, test_calc_beam_invalid_args);
210  FRIEND_TEST(OS32CTest, test_convert_to_laserscan);
211 
212  double start_angle_;
213  double end_angle_;
214 
215  // data for sending to lidar to keep UDP session alive
219 
226  void calcBeamMask(double start_angle, double end_angle, EIP_BYTE mask[]);
227 };
228 
229 } // namespace omron_os32c_driver
230 
231 #endif // OMRON_OS32C_DRIVER_OS32C_H
MeasurementReportConfig mrc_
Definition: os32c.h:217
static const double ANGLE_INC
Definition: os32c.h:93
void selectBeams(double start_angle, double end_angle)
Definition: os32c.cpp:138
EIP_UINT getReflectivityFormat()
Definition: os32c.cpp:73
static const double ANGLE_MAX
Definition: os32c.h:92
RangeAndReflectanceMeasurement getSingleRRScan()
Definition: os32c.cpp:145
OS32C_REFLECTIVITY_FORMAT
Definition: os32c.h:63
static int calcBeamNumber(double angle)
Definition: os32c.h:157
void setReflectivityFormat(EIP_UINT format)
Definition: os32c.cpp:79
void setRangeFormat(EIP_UINT format)
Definition: os32c.cpp:67
OS32C(shared_ptr< Socket > socket, shared_ptr< Socket > io_socket)
Definition: os32c.h:82
EIP_UINT getRangeFormat()
Definition: os32c.cpp:61
uint8_t EIP_BYTE
static double calcBeamCentre(int beam_num)
Definition: os32c.h:168
static const double DISTANCE_MAX
Definition: os32c.h:95
uint16_t EIP_UINT
void calcBeamMask(double start_angle, double end_angle, EIP_BYTE mask[])
Definition: os32c.cpp:85
MeasurementReport receiveMeasurementReportUDP()
Definition: os32c.cpp:244
EIP_UDINT mrc_sequence_num_
Definition: os32c.h:218
static const double ANGLE_MIN
Definition: os32c.h:91
static void convertToLaserScan(const RangeAndReflectanceMeasurement &rr, sensor_msgs::LaserScan *ls)
Definition: os32c.cpp:161
uint32_t EIP_UDINT
void sendMeasurmentReportConfigUDP()
Definition: os32c.cpp:231
void fillLaserScanStaticConfig(sensor_msgs::LaserScan *ls)
Definition: os32c.cpp:152
FRIEND_TEST(OS32CTest, test_calc_beam_mask_all)
static const double DISTANCE_MIN
Definition: os32c.h:94


omron_os32c_driver
Author(s): Kareem Shehata
autogenerated on Fri Nov 27 2020 03:06:12