Public Member Functions | Static Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
omron_os32c_driver::OS32C Class Reference

#include <os32c.h>

Inheritance diagram for omron_os32c_driver::OS32C:
Inheritance graph
[legend]

Public Member Functions

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 ()
 
- Public Member Functions inherited from eip::Session
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 ConnectiongetConnection (size_t n)
 
EIP_UDINT getSerialNum () const
 
EIP_UDINT getSessionID ()
 
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 ()
 

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_
 

Detailed Description

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.

Constructor & Destructor Documentation

omron_os32c_driver::OS32C::OS32C ( shared_ptr< Socket socket,
shared_ptr< Socket io_socket 
)
inline

Construct a new OS32C instance.

Parameters
socketSocket instance to use for communication with the lidar

Definition at line 82 of file os32c.h.

Member Function Documentation

static double omron_os32c_driver::OS32C::calcBeamCentre ( int  beam_num)
inlinestatic

Calculate the ROS angle for a beam given the OS32C beam number

Parameters
beam_numBeam number, starting with 0 being the most CCW beam and positive moving CW around the scan
Returns
ROS Angle

Definition at line 168 of file os32c.h.

void omron_os32c_driver::OS32C::calcBeamMask ( double  start_angle,
double  end_angle,
EIP_BYTE  mask[] 
)
private

Helper to calculate the mask for a given start and end beam angle

Parameters
start_angleAngle of the first beam in the scan
end_angleAngle of the last beam in the scan
maskHolder for the mask data. Must be 88 bytes

Definition at line 85 of file os32c.cpp.

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
angleRadians CCW from straight ahead
Returns
OS32C beam number

Definition at line 157 of file os32c.h.

void omron_os32c_driver::OS32C::closeActiveConnection ( )

Definition at line 275 of file os32c.cpp.

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.

Parameters
rrMeasurement to convert
lsLaserscan message to populate.

Definition at line 161 of file os32c.cpp.

void omron_os32c_driver::OS32C::convertToLaserScan ( const MeasurementReport mr,
sensor_msgs::LaserScan *  ls 
)
static

Helper to convert a Measurement Report to a ROS LaserScan

Parameters
mrMeasurement to convert
lsLaserscan message to populate.

Definition at line 197 of file os32c.cpp.

void omron_os32c_driver::OS32C::fillLaserScanStaticConfig ( sensor_msgs::LaserScan *  ls)

Populate the unchanging parts of a ROS LaserScan, including the start_angle and stop_angle, which are configured by the user but ultimately reported by the device.

Parameters
lsLaserscan message to populate.

Definition at line 152 of file os32c.cpp.

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
EIP_UINT omron_os32c_driver::OS32C::getRangeFormat ( )

Get the range format code. Does a Get Single Attribute to the scanner to get the current range format.

Returns
range format code.
See also
OS32C_RANGE_FORMAT

Definition at line 61 of file os32c.cpp.

EIP_UINT omron_os32c_driver::OS32C::getReflectivityFormat ( )

Get the reflectivity format code. Does a Get Single Attribute to the scanner to get the current reflectivity format.

Returns
reflectivity format code.
See also
OS32C_REFLECTIVITY_FORMAT

Definition at line 73 of file os32c.cpp.

RangeAndReflectanceMeasurement omron_os32c_driver::OS32C::getSingleRRScan ( )

Make an explicit request for a single Range and Reflectance scan

Returns
Range and reflectance data received
Exceptions
std::logic_errorif data not received

Definition at line 145 of file os32c.cpp.

MeasurementReport omron_os32c_driver::OS32C::receiveMeasurementReportUDP ( )

Definition at line 244 of file os32c.cpp.

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.

Parameters
start_angleStart angle in ROS conventions
end_angleEnd angle in ROS conventions

Definition at line 138 of file os32c.cpp.

void omron_os32c_driver::OS32C::sendMeasurmentReportConfigUDP ( )

Definition at line 231 of file os32c.cpp.

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.

Parameters
formatThe range format code to set
See also
OS32C_REFLECTIVITY_FORMAT

Definition at line 67 of file os32c.cpp.

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.

Parameters
formatThe reflectivity format code to set
See also
OS32C_RANGE_FORMAT

Definition at line 79 of file os32c.cpp.

void omron_os32c_driver::OS32C::startUDPIO ( )

Definition at line 261 of file os32c.cpp.

Member Data Documentation

const double omron_os32c_driver::OS32C::ANGLE_INC = DEG2RAD(0.4)
static

Definition at line 93 of file os32c.h.

const double omron_os32c_driver::OS32C::ANGLE_MAX = DEG2RAD(135.2)
static

Definition at line 92 of file os32c.h.

const double omron_os32c_driver::OS32C::ANGLE_MIN = DEG2RAD(-135.2)
static

Definition at line 91 of file os32c.h.

int omron_os32c_driver::OS32C::connection_num_
private

Definition at line 216 of file os32c.h.

const double omron_os32c_driver::OS32C::DISTANCE_MAX = 50
static

Definition at line 95 of file os32c.h.

const double omron_os32c_driver::OS32C::DISTANCE_MIN = 0.002
static

Definition at line 94 of file os32c.h.

double omron_os32c_driver::OS32C::end_angle_
private

Definition at line 213 of file os32c.h.

MeasurementReportConfig omron_os32c_driver::OS32C::mrc_
private

Definition at line 217 of file os32c.h.

EIP_UDINT omron_os32c_driver::OS32C::mrc_sequence_num_
private

Definition at line 218 of file os32c.h.

double omron_os32c_driver::OS32C::start_angle_
private

Definition at line 212 of file os32c.h.


The documentation for this class was generated from the following files:


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