#include <os32c.h>
Public Member Functions | |
void | fillLaserScanStaticConfig (sensor_msgs::LaserScan *ls) |
EIP_UINT | getRangeFormat () |
EIP_UINT | getReflectivityFormat () |
RangeAndReflectanceMeasurement | getSingleRRScan () |
OS32C (shared_ptr< Socket > socket, shared_ptr< Socket > io_socket) | |
MeasurementReport | receiveMeasurementReportUDP () |
void | selectBeams (double start_angle, double end_angle) |
void | sendMeasurmentReportConfigUDP () |
void | setRangeFormat (EIP_UINT format) |
void | setReflectivityFormat (EIP_UINT format) |
void | startUDPIO () |
Static Public Member Functions | |
static double | calcBeamCentre (int beam_num) |
static int | calcBeamNumber (double angle) |
static void | convertToLaserScan (const RangeAndReflectanceMeasurement &rr, sensor_msgs::LaserScan *ls) |
static void | convertToLaserScan (const MeasurementReport &mr, sensor_msgs::LaserScan *ls) |
Static Public Attributes | |
static const double | ANGLE_INC = DEG2RAD(0.4) |
static const double | ANGLE_MAX = DEG2RAD( 135.2) |
static const double | ANGLE_MIN = DEG2RAD(-135.2) |
static const double | DISTANCE_MAX = 50 |
static const double | DISTANCE_MIN = 0.002 |
Private Member Functions | |
void | calcBeamMask (double start_angle, double end_angle, EIP_BYTE mask[]) |
FRIEND_TEST (OS32CTest, test_calc_beam_mask_all) | |
FRIEND_TEST (OS32CTest, test_calc_beam_at_90) | |
FRIEND_TEST (OS32CTest, test_calc_beam_boundaries) | |
FRIEND_TEST (OS32CTest, test_calc_beam_invalid_args) | |
FRIEND_TEST (OS32CTest, test_convert_to_laserscan) | |
Private Attributes | |
int | connection_num_ |
double | end_angle_ |
MeasurementReportConfig | mrc_ |
EIP_UDINT | mrc_sequence_num_ |
double | start_angle_ |
Main interface for the OS32C Laser Scanner. Produces methods to access the laser scanner from a high level, including setting parameters and getting single scans.
omron_os32c_driver::OS32C::OS32C | ( | shared_ptr< Socket > | socket, |
shared_ptr< Socket > | io_socket | ||
) | [inline] |
static double omron_os32c_driver::OS32C::calcBeamCentre | ( | int | beam_num | ) | [inline, static] |
void omron_os32c_driver::OS32C::calcBeamMask | ( | double | start_angle, |
double | end_angle, | ||
EIP_BYTE | mask[] | ||
) | [private] |
static int omron_os32c_driver::OS32C::calcBeamNumber | ( | double | angle | ) | [inline, static] |
Calculate the beam number on the lidar for a given ROS angle. Note that in ROS angles are given as radians CCW with zero being straight ahead, While the lidar start its scan at the most CCW position and moves positive CW, with zero being at halfway through the scan. Based on my calculations and the OS32C docs, there are 677 beams and the scan area is 135.4 to -135.4 degrees, with a 0.4 degree pitch. The beam centres must then be at 135.2, 134.8, ... 0.4, 0, 0.4, ... -134.8, -135.2.
angle | Radians CCW from straight ahead |
void omron_os32c_driver::OS32C::convertToLaserScan | ( | const RangeAndReflectanceMeasurement & | rr, |
sensor_msgs::LaserScan * | ls | ||
) | [static] |
Helper to convert a Range and Reflectance Measurement to a ROS LaserScan. LaserScan is passed as a pointer to avoid a bunch of memory allocation associated with resizing a vector on each scan.
rr | Measurement to convert |
ls | Laserscan message to populate. |
void omron_os32c_driver::OS32C::convertToLaserScan | ( | const MeasurementReport & | mr, |
sensor_msgs::LaserScan * | ls | ||
) | [static] |
void omron_os32c_driver::OS32C::fillLaserScanStaticConfig | ( | sensor_msgs::LaserScan * | ls | ) |
omron_os32c_driver::OS32C::FRIEND_TEST | ( | OS32CTest | , |
test_calc_beam_mask_all | |||
) | [private] |
omron_os32c_driver::OS32C::FRIEND_TEST | ( | OS32CTest | , |
test_calc_beam_at_90 | |||
) | [private] |
omron_os32c_driver::OS32C::FRIEND_TEST | ( | OS32CTest | , |
test_calc_beam_boundaries | |||
) | [private] |
omron_os32c_driver::OS32C::FRIEND_TEST | ( | OS32CTest | , |
test_calc_beam_invalid_args | |||
) | [private] |
omron_os32c_driver::OS32C::FRIEND_TEST | ( | OS32CTest | , |
test_convert_to_laserscan | |||
) | [private] |
Get the range format code. Does a Get Single Attribute to the scanner to get the current range format.
Get the reflectivity format code. Does a Get Single Attribute to the scanner to get the current reflectivity format.
void omron_os32c_driver::OS32C::selectBeams | ( | double | start_angle, |
double | end_angle | ||
) |
Select which beams are to be measured. Must be set before requesting measurements. Angles are in ROS conventions. Zero is straight ahead. Positive numbers are CCW and all numbers are in radians.
start_angle | Start angle in ROS conventions |
end_angle | End angle in ROS conventions |
void omron_os32c_driver::OS32C::setRangeFormat | ( | EIP_UINT | format | ) |
Set the range format code for the scanner. Does a Set Single Attribute to the scanner to set the range format.
format | The range format code to set |
void omron_os32c_driver::OS32C::setReflectivityFormat | ( | EIP_UINT | format | ) |
Set the reflectivity format code for the scanner. Does a Set Single Attribute to the scanner to set the reflectivity format.
format | The reflectivity format code to set |
const double omron_os32c_driver::OS32C::ANGLE_INC = DEG2RAD(0.4) [static] |
const double omron_os32c_driver::OS32C::ANGLE_MAX = DEG2RAD( 135.2) [static] |
const double omron_os32c_driver::OS32C::ANGLE_MIN = DEG2RAD(-135.2) [static] |
int omron_os32c_driver::OS32C::connection_num_ [private] |
const double omron_os32c_driver::OS32C::DISTANCE_MAX = 50 [static] |
const double omron_os32c_driver::OS32C::DISTANCE_MIN = 0.002 [static] |
double omron_os32c_driver::OS32C::end_angle_ [private] |
double omron_os32c_driver::OS32C::start_angle_ [private] |