|
void | closeActiveConnection () |
|
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 () |
|
void | close () |
|
void | closeConnection (size_t n) |
|
int | createConnection (const EIP_CONNECTION_INFO_T &o_to_t, const EIP_CONNECTION_INFO_T &t_to_o) |
|
const Connection & | getConnection (size_t n) |
|
EIP_UDINT | getSerialNum () const |
|
EIP_UDINT | getSessionID () |
|
T | getSingleAttribute (EIP_USINT class_id, EIP_USINT instance_id, EIP_USINT attribute_id, T v) |
|
void | getSingleAttributeSerializable (EIP_USINT class_id, EIP_USINT instance_id, EIP_USINT attribute_id, Serializable &result) |
|
EIP_UINT | getVendorID () const |
|
void | open (string hostname, string port="44818", string io_port="2222") |
|
CPFPacket | receiveIOPacket () |
|
void | sendIOPacket (CPFPacket &pkt) |
|
| Session (shared_ptr< Socket > socket, shared_ptr< Socket > io_socket, EIP_UINT vendor_id=DEFAULT_VENDOR_ID, EIP_UDINT serial_num=DEFAULT_SERIAL_NUM) |
|
void | setSingleAttribute (EIP_USINT class_id, EIP_USINT instance_id, EIP_USINT attribute_id, T v) |
|
void | setSingleAttributeSerializable (EIP_USINT class_id, EIP_USINT instance_id, EIP_USINT attribute_id, shared_ptr< Serializable > data) |
|
virtual | ~Session () |
|
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.
Definition at line 75 of file os32c.h.
static int omron_os32c_driver::OS32C::calcBeamNumber |
( |
double |
angle | ) |
|
|
inlinestatic |
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.
- Parameters
-
angle | Radians CCW from straight ahead |
- Returns
- OS32C beam number
Definition at line 157 of file os32c.h.