26 #ifndef OMRON_OS32C_DRIVER_OS32C_H 27 #define OMRON_OS32C_DRIVER_OS32C_H 29 #include <gtest/gtest_prod.h> 32 #include <boost/shared_ptr.hpp> 33 #include <sensor_msgs/LaserScan.h> 43 using sensor_msgs::LaserScan;
47 #define DEG2RAD(a) (a * M_PI / 180) 48 #define RAD2DEG(a) (a * 180 / M_PI) 137 void selectBeams(
double start_angle,
double end_angle);
159 return (ANGLE_MAX - angle + ANGLE_INC / 2) /
ANGLE_INC;
231 #endif // OMRON_OS32C_DRIVER_OS32C_H MeasurementReportConfig mrc_
static const double ANGLE_INC
void selectBeams(double start_angle, double end_angle)
EIP_UINT getReflectivityFormat()
static const double ANGLE_MAX
RangeAndReflectanceMeasurement getSingleRRScan()
OS32C_REFLECTIVITY_FORMAT
static int calcBeamNumber(double angle)
void setReflectivityFormat(EIP_UINT format)
void setRangeFormat(EIP_UINT format)
void closeActiveConnection()
OS32C(shared_ptr< Socket > socket, shared_ptr< Socket > io_socket)
EIP_UINT getRangeFormat()
static double calcBeamCentre(int beam_num)
static const double DISTANCE_MAX
void calcBeamMask(double start_angle, double end_angle, EIP_BYTE mask[])
MeasurementReport receiveMeasurementReportUDP()
EIP_UDINT mrc_sequence_num_
static const double ANGLE_MIN
static void convertToLaserScan(const RangeAndReflectanceMeasurement &rr, sensor_msgs::LaserScan *ls)
void sendMeasurmentReportConfigUDP()
void fillLaserScanStaticConfig(sensor_msgs::LaserScan *ls)
FRIEND_TEST(OS32CTest, test_calc_beam_mask_all)
static const double DISTANCE_MIN