Classes | Public Types | Public Member Functions | Static Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
SickToolbox::SickLMS1xx Class Reference

Provides a simple driver interface for working with the Sick LD-OEM/Sick LD-LRS long-range models via Ethernet. More...

#include <SickLMS1xx.hh>

Inheritance diagram for SickToolbox::SickLMS1xx:
Inheritance graph
[legend]

Classes

struct  sick_lms_1xx_scan_config_tag
 A structure for aggregrating the Sick LMS 1xx configuration params. More...
 

Public Types

enum  sick_lms_1xx_scan_format_t {
  SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_NONE = 0x00, SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_8BIT = 0x01, SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_16BIT = 0x02, SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_NONE = 0x03,
  SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_8BIT = 0x04, SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_16BIT = 0x05, SICK_LMS_1XX_SCAN_FORMAT_UNKNOWN = 0xFF
}
 Defines the Sick LMS 1xx scan types This enum is for specifiying the desired scan returns. More...
 
enum  sick_lms_1xx_scan_freq_t { SICK_LMS_1XX_SCAN_FREQ_UNKNOWN = 0x00, SICK_LMS_1XX_SCAN_FREQ_25 = 0x09C4, SICK_LMS_1XX_SCAN_FREQ_50 = 0X1388 }
 Defines the Sick LMS 1xx scan frequency. This enum lists all of the Sick LMS 1xx scan frequencies. More...
 
enum  sick_lms_1xx_scan_res_t { SICK_LMS_1XX_SCAN_RES_UNKNOWN = 0x00, SICK_LMS_1XX_SCAN_RES_25 = 0x09C4, SICK_LMS_1XX_SCAN_RES_50 = 0x1388 }
 Defines the Sick LMS 1xx scan resolution. This enum lists all of the Sick LMS 1xx scan resolutions. More...
 
enum  sick_lms_1xx_status_t {
  SICK_LMS_1XX_STATUS_UNKNOWN = 0x00, SICK_LMS_1XX_STATUS_INITIALIZATION = 0x01, SICK_LMS_1XX_STATUS_CONFIGURATION = 0x02, SICK_LMS_1XX_STATUS_IDLE = 0x03,
  SICK_LMS_1XX_STATUS_ROTATED = 0x04, SICK_LMS_1XX_STATUS_IN_PREP = 0x05, SICK_LMS_1XX_STATUS_READY = 0x06, SICK_LMS_1XX_STATUS_READY_FOR_MEASUREMENT = 0x07
}
 Defines the Sick LMS 1xx status. This enum lists all of the Sick LMS 1xx status. More...
 

Public Member Functions

sick_lms_1xx_scan_res_t DoubleToSickScanRes (const double scan_res) const
 Convert double to corresponding sick_lms_1xx_scan_res_t. More...
 
void GetSickMeasurements (unsigned int *const range_1_vals, unsigned int *const range_2_vals, unsigned int *const reflect_1_vals, unsigned int *const reflect_2_vals, unsigned int &num_measurements, unsigned int *const dev_status=NULL) throw ( SickIOException, SickConfigException, SickTimeoutException )
 Acquire multi-pulse sick range measurements. More...
 
sick_lms_1xx_scan_freq_t GetSickScanFreq () const throw ( SickIOException )
 Gets the Sick LMS 1xx scan frequency. More...
 
sick_lms_1xx_scan_res_t GetSickScanRes () const throw ( SickIOException )
 Gets the Sick LMS 1xx scan resolution. More...
 
double GetSickStartAngle () const throw ( SickIOException )
 Gets the Sick LMS 1xx scan area start angle [-45,270] deg. More...
 
double GetSickStopAngle () const throw ( SickIOException )
 Gets the Sick LMS 1xx scan area start angle [-45,270] deg. More...
 
void Initialize (const bool disp_banner=true) throw ( SickIOException, SickThreadException, SickTimeoutException, SickErrorException )
 Initializes the driver and syncs it with Sick LMS 1xx unit. Uses flash params. More...
 
sick_lms_1xx_scan_freq_t IntToSickScanFreq (const int scan_freq) const
 Convert integer to corresponding sick_lms_1xx_scan_freq_t. More...
 
void SetSickScanDataFormat (const sick_lms_1xx_scan_format_t scan_format) throw ( SickTimeoutException, SickIOException, SickThreadException, SickErrorException )
 
void SetSickScanFreqAndRes (const sick_lms_1xx_scan_freq_t scan_freq, const sick_lms_1xx_scan_res_t scan_res) throw ( SickTimeoutException, SickIOException, SickErrorException )
 Sets the Sick LMS 1xx scan frequency and resolution. More...
 
 SickLMS1xx (const std::string sick_ip_address=DEFAULT_SICK_LMS_1XX_IP_ADDRESS, const uint16_t sick_tcp_port=DEFAULT_SICK_LMS_1XX_TCP_PORT)
 A standard constructor. More...
 
int SickScanFreqToInt (const sick_lms_1xx_scan_freq_t scan_freq) const
 Convert sick_lms_1xx_scan_freq_t to corresponding integer. More...
 
double SickScanResToDouble (const sick_lms_1xx_scan_res_t scan_res) const
 Convert sick_lms_1xx_scan_res_t to corresponding double. More...
 
void Uninitialize (const bool disp_banner=true) throw ( SickIOException, SickTimeoutException, SickErrorException, SickThreadException )
 Tear down the connection between the host and the Sick LD. More...
 
 ~SickLMS1xx ()
 
- Public Member Functions inherited from SickToolbox::SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >
bool IsInitialized ()
 
 SickLIDAR ()
 Initializes the buffer monitor. More...
 
virtual ~SickLIDAR ()
 Destructor tears down buffer monitor. More...
 

Static Public Attributes

static const int SICK_LMS_1XX_MAX_NUM_MEASUREMENTS = 1082
 LMS 1xx max number of measurements. More...
 

Private Types

typedef struct SickToolbox::SickLMS1xx::sick_lms_1xx_scan_config_tag sick_lms_1xx_scan_config_t
 Adopt c-style convention. More...
 

Private Member Functions

void _checkForMeasuringStatus (unsigned int timeout_value=DEFAULT_SICK_LMS_1XX_STATUS_TIMEOUT) throw ( SickTimeoutException, SickIOException )
 Attempts to set and waits until device has in measuring status. More...
 
char * _convertNextTokenToUInt (char *const str_buffer, unsigned int &num_val, const char *const delimeter=" ") const
 Utility function for converting next token into unsigned int. More...
 
double _convertSickAngleUnitsToDegs (const int sick_angle) const
 
unsigned int _convertSickFreqUnitsToHz (const unsigned int sick_freq) const
 
bool _findSubString (const char *const str, const char *const substr, const unsigned int str_length, const unsigned int substr_length, unsigned int &substr_pos, unsigned int start_pos=0) const
 Searches a string for a substring. More...
 
void _getSickScanConfig () throw ( SickTimeoutException, SickIOException )
 Get the scan configuration of the Sick LMS 1xx. More...
 
std::string _intToSickConfigErrorStr (const int error) const
 
sick_lms_1xx_status_t _intToSickStatus (const int status) const
 Converts int to status. More...
 
void _printInitFooter () const
 Prints the initialization footer. More...
 
void _printSickScanConfig () const
 Prints Sick LMS 1xx scan configuration. More...
 
void _recvMessage (SickLMS1xxMessage &sick_message) const throw ( SickTimeoutException )
 Receive a message. More...
 
void _reinitialize () throw ( SickIOException, SickThreadException, SickTimeoutException, SickErrorException )
 Re-initializes the Sick LMS 1xx. More...
 
void _requestDataStream () throw ( SickTimeoutException, SickConfigException, SickIOException )
 Request a data data stream type. More...
 
void _restoreMeasuringMode () throw ( SickTimeoutException, SickIOException )
 
void _sendMessage (const SickLMS1xxMessage &send_message) const throw ( SickIOException )
 Sends a message without waiting for reply. More...
 
void _sendMessageAndGetReply (const SickLMS1xxMessage &send_message, SickLMS1xxMessage &recv_message, const std::string reply_command_code, const std::string reply_command, const unsigned int timeout_value=DEFAULT_SICK_LMS_1XX_MESSAGE_TIMEOUT, const unsigned int num_tries=1) throw ( SickIOException, SickTimeoutException )
 Sends a message and searches for the reply with given command type and command. More...
 
void _setAuthorizedClientAccessMode () throw ( SickTimeoutException, SickErrorException, SickIOException )
 Login as an authorized client. More...
 
void _setSickScanConfig (const sick_lms_1xx_scan_freq_t scan_freq, const sick_lms_1xx_scan_res_t scan_res, const int start_angle, const int stop_angle) throw ( SickTimeoutException, SickIOException, SickErrorException )
 Set the Sick LMS 1xx scan configuration (volatile, does not write to EEPROM) More...
 
void _setSickScanDataFormat (const sick_lms_1xx_scan_format_t scan_format) throw ( SickTimeoutException, SickIOException, SickThreadException, SickErrorException )
 
void _setupConnection () throw ( SickIOException, SickTimeoutException )
 Establish a TCP connection to the unit. More...
 
std::string _sickScanDataFormatToString (const sick_lms_1xx_scan_format_t scan_format) const
 Utility function for returning scan format as string. More...
 
void _startMeasuring () throw ( SickTimeoutException, SickIOException )
 Tell the device to start measuring. More...
 
void _startStreamingMeasurements () throw ( SickTimeoutException, SickIOException )
 
void _stopMeasuring () throw ( SickTimeoutException, SickIOException )
 Tell the device to start measuring. More...
 
void _stopStreamingMeasurements (const bool disp_banner=true) throw ( SickTimeoutException, SickIOException )
 Stop Measurment Stream. More...
 
void _teardownConnection () throw ( SickIOException )
 Teardown TCP connection to Sick LMS 1xx. More...
 
void _updateSickStatus () throw ( SickTimeoutException, SickIOException )
 Get the status of the Sick LMS 1xx. More...
 
bool _validScanArea (const int start_angle, const int stop_angle) const
 Utility function to ensure valid scan area. More...
 
void _writeToEEPROM () throw ( SickTimeoutException, SickIOException )
 Login as an authorized client. More...
 

Private Attributes

sick_lms_1xx_status_t _sick_device_status
 
struct sockaddr_in _sick_inet_address_info
 
std::string _sick_ip_address
 
sick_lms_1xx_scan_config_t _sick_scan_config
 
sick_lms_1xx_scan_format_t _sick_scan_format
 
bool _sick_streaming
 
uint16_t _sick_tcp_port
 
bool _sick_temp_safe
 

Additional Inherited Members

- Protected Member Functions inherited from SickToolbox::SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >
double _computeElapsedTime (const struct timeval &beg_time, const struct timeval &end_time) const
 
bool _monitorRunning () const
 
void _recvMessage (SickLMS1xxMessage &sick_message, const unsigned int timeout_value) const throw ( SickTimeoutException )
 Attempt to acquire the latest available message from the device. More...
 
void _recvMessage (SickLMS1xxMessage &sick_message, const uint8_t *const byte_sequence, const unsigned int byte_sequence_length, const unsigned int timeout_value) const throw ( SickTimeoutException )
 Attempt to acquire a message having a payload beginning w/ the given byte sequence. More...
 
void _sendMessage (const SickLMS1xxMessage &sick_message, const unsigned int byte_interval) const throw ( SickIOException )
 Sends a message to the Sick device. More...
 
virtual void _sendMessageAndGetReply (const SickLMS1xxMessage &send_message, SickLMS1xxMessage &recv_message, const uint8_t *const byte_sequence, const unsigned int byte_sequence_length, const unsigned int byte_interval, const unsigned int timeout_value, const unsigned int num_tries) throw ( SickTimeoutException, SickIOException)
 
void _setBlockingIO () const throw ( SickIOException )
 A simple method for setting blocking I/O. More...
 
void _setNonBlockingIO () const throw ( SickIOException )
 A simple method for setting non-blocking I/O. More...
 
void _startListening () throw ( SickThreadException )
 Activates the buffer monitor for the driver. More...
 
void _stopListening () throw ( SickThreadException )
 Activates the buffer monitor for the driver. More...
 
- Protected Attributes inherited from SickToolbox::SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >
SickLMS1xxBufferMonitor_sick_buffer_monitor
 
int _sick_fd
 
bool _sick_initialized
 
bool _sick_monitor_running
 

Detailed Description

Provides a simple driver interface for working with the Sick LD-OEM/Sick LD-LRS long-range models via Ethernet.

Definition at line 50 of file SickLMS1xx.hh.

Member Typedef Documentation

Adopt c-style convention.

Member Enumeration Documentation

Defines the Sick LMS 1xx scan types This enum is for specifiying the desired scan returns.

Enumerator
SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_NONE 

Single-pulse dist, no reflect.

SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_8BIT 

Single-pulse dist, 8bit reflect.

SICK_LMS_1XX_SCAN_FORMAT_DIST_SINGLE_PULSE_REFLECT_16BIT 

Single-pulse dist, 16bit reflect.

SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_NONE 

Double-pulse dist, no reflect.

SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_8BIT 

Double-pulse dist, 8bit reflect.

SICK_LMS_1XX_SCAN_FORMAT_DIST_DOUBLE_PULSE_REFLECT_16BIT 

Double-pulse dist, 16bit reflect.

SICK_LMS_1XX_SCAN_FORMAT_UNKNOWN 

Unknown format.

Definition at line 79 of file SickLMS1xx.hh.

Defines the Sick LMS 1xx scan frequency. This enum lists all of the Sick LMS 1xx scan frequencies.

Enumerator
SICK_LMS_1XX_SCAN_FREQ_UNKNOWN 

LMS 1xx scan freq unknown.

SICK_LMS_1XX_SCAN_FREQ_25 

LMS 1xx scan freq 25Hz.

SICK_LMS_1XX_SCAN_FREQ_50 

LMS 1xx scan freq 50Hz.

Definition at line 96 of file SickLMS1xx.hh.

Defines the Sick LMS 1xx scan resolution. This enum lists all of the Sick LMS 1xx scan resolutions.

Enumerator
SICK_LMS_1XX_SCAN_RES_UNKNOWN 

LMS 1xx scab res unknown.

SICK_LMS_1XX_SCAN_RES_25 

LMS 1xx scan res 0.25 deg.

SICK_LMS_1XX_SCAN_RES_50 

LMS 1xx scan res 0.50 deg.

Definition at line 109 of file SickLMS1xx.hh.

Defines the Sick LMS 1xx status. This enum lists all of the Sick LMS 1xx status.

Enumerator
SICK_LMS_1XX_STATUS_UNKNOWN 

LMS 1xx status undefined.

SICK_LMS_1XX_STATUS_INITIALIZATION 

LMS 1xx initializing.

SICK_LMS_1XX_STATUS_CONFIGURATION 

LMS 1xx configuration.

SICK_LMS_1XX_STATUS_IDLE 

LMS 1xx is idle.

SICK_LMS_1XX_STATUS_ROTATED 

LMS 1xx mirror rotating.

SICK_LMS_1XX_STATUS_IN_PREP 

LMS 1xx in preparation.

SICK_LMS_1XX_STATUS_READY 

LMS 1xx is ready.

SICK_LMS_1XX_STATUS_READY_FOR_MEASUREMENT 

LMS 1xx is ready to give measurements.

Definition at line 61 of file SickLMS1xx.hh.

Constructor & Destructor Documentation

SickToolbox::SickLMS1xx::SickLMS1xx ( const std::string  sick_ip_address = DEFAULT_SICK_LMS_1XX_IP_ADDRESS,
const uint16_t  sick_tcp_port = DEFAULT_SICK_LMS_1XX_TCP_PORT 
)

A standard constructor.

Primary constructor

Parameters
sick_ip_addressThe ip address of the Sick LD
sick_tcp_portThe TCP port associated w/ the Sick LD server

Definition at line 52 of file SickLMS1xx.cc.

SickToolbox::SickLMS1xx::~SickLMS1xx ( )

Destructor

A standard destructor

Definition at line 67 of file SickLMS1xx.cc.

Member Function Documentation

void SickToolbox::SickLMS1xx::_checkForMeasuringStatus ( unsigned int  timeout_value = DEFAULT_SICK_LMS_1XX_STATUS_TIMEOUT)
throw ( SickTimeoutException,
SickIOException
)
private

Attempts to set and waits until device has in measuring status.

Set device to measuring mode

Parameters
timeout_valueTimeout value in usecs

Definition at line 1730 of file SickLMS1xx.cc.

char * SickToolbox::SickLMS1xx::_convertNextTokenToUInt ( char *const  str_buffer,
unsigned int &  num_val,
const char *const  delimeter = " " 
) const
private

Utility function for converting next token into unsigned int.

Utility function for extracting next integer from tokenized string

Parameters
str_bufferSource (c-string) buffer
next_tokenPointer to the next string token
delimeterToken delimiter (default is " ")
Returns
Unsigned integer corresponding to numeric string token value

Definition at line 2275 of file SickLMS1xx.cc.

double SickToolbox::SickLMS1xx::_convertSickAngleUnitsToDegs ( const int  sick_angle) const
inlineprivate

Utility function for converting sick freq to doubles

Definition at line 291 of file SickLMS1xx.hh.

unsigned int SickToolbox::SickLMS1xx::_convertSickFreqUnitsToHz ( const unsigned int  sick_freq) const
inlineprivate

Utility function for converting sick Hz values ints

Definition at line 294 of file SickLMS1xx.hh.

bool SickToolbox::SickLMS1xx::_findSubString ( const char *const  str,
const char *const  substr,
const unsigned int  str_length,
const unsigned int  substr_length,
unsigned int &  substr_pos,
unsigned int  start_pos = 0 
) const
private

Searches a string for a substring.

Utility function to locate substring in string

Parameters
strString to be searched
substrSubstring being sought
str_lengthString's length
substr_lengthSubstring's length
substr_posReference holding the location in the main string where substr was found
start_posIndex into main string to indicate where to start searching
Returns
True if substring found, false otherwise

Definition at line 2242 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_getSickScanConfig ( )
throw ( SickTimeoutException,
SickIOException
)
private

Get the scan configuration of the Sick LMS 1xx.

Acquire the Sick LMS's scan config

Definition at line 918 of file SickLMS1xx.cc.

std::string SickToolbox::SickLMS1xx::_intToSickConfigErrorStr ( const int  error) const
private

Utility function to convert config error int to str

Definition at line 2162 of file SickLMS1xx.cc.

sick_lms_1xx_status_t SickToolbox::SickLMS1xx::_intToSickStatus ( const int  status) const
private

Converts int to status.

Utility function to convert int to status

Parameters
statusinteger corresponding to sick status

Definition at line 2139 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_printInitFooter ( ) const
private

Prints the initialization footer.

Utility function for printing footer after initialization

Definition at line 2195 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_printSickScanConfig ( ) const
private

Prints Sick LMS 1xx scan configuration.

Utility function for printing Sick scan config

Definition at line 2182 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_recvMessage ( SickLMS1xxMessage sick_message) const
throw (SickTimeoutException
)
private

Receive a message.

Receive a message

Parameters
sick_messageReference to container to hold received message

Definition at line 2113 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_reinitialize ( )
throw ( SickIOException,
SickThreadException,
SickTimeoutException,
SickErrorException
)
private

Re-initializes the Sick LMS 1xx.

Re-initialized the device

Definition at line 790 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_requestDataStream ( )
throw ( SickTimeoutException,
SickConfigException,
SickIOException
)
private

Request a data data stream type.

Request a data data stream type

Parameters
dist_optDesired distance returns (single-pulse or multi-pulse)
reflect_optDesired reflectivity returns (none, 8-bit or 16-bit)

Definition at line 1549 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_restoreMeasuringMode ( )
throw ( SickTimeoutException,
SickIOException
)
private

Restore device to measuring mode

Set device to output only range values

Definition at line 1950 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_sendMessage ( const SickLMS1xxMessage send_message) const
throw (SickIOException
)
private

Sends a message without waiting for reply.

Send the message w/o waiting for a reply

Definition at line 2038 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_sendMessageAndGetReply ( const SickLMS1xxMessage send_message,
SickLMS1xxMessage recv_message,
const std::string  reply_command_type,
const std::string  reply_command,
const unsigned int  timeout_value = DEFAULT_SICK_LMS_1XX_MESSAGE_TIMEOUT,
const unsigned int  num_tries = 1 
)
throw ( SickIOException,
SickTimeoutException
)
private

Sends a message and searches for the reply with given command type and command.

Send the message and grab expected reply

Parameters
&send_messageThe message to be sent to the Sick LMS 2xx unit
&recv_messageThe expected message reply from the Sick LMS
reply_command_codeThe expected command code for the recv_message
reply_commandThe expected command for the recv_message
timeout_valueThe epoch to wait before considering a sent frame lost (in usecs)
num_triesThe number of times to send the message in the event the LMS fails to reply

Definition at line 2072 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_setAuthorizedClientAccessMode ( )
throw ( SickTimeoutException,
SickErrorException,
SickIOException
)
private

Login as an authorized client.

Set access mode for configuring device

Definition at line 1236 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_setSickScanConfig ( const sick_lms_1xx_scan_freq_t  scan_freq,
const sick_lms_1xx_scan_res_t  scan_res,
const int  start_angle,
const int  stop_angle 
)
throw ( SickTimeoutException,
SickIOException,
SickErrorException
)
private

Set the Sick LMS 1xx scan configuration (volatile, does not write to EEPROM)

Sets the scan configuration (volatile, does not write to EEPROM)

Parameters
scan_freqDesired scan frequency (Either SickLMS1xx::SICK_LMS_1XX_SCAN_FREQ_25 or SickLMS1xx::SICK_LMS_1XX_SCAN_FREQ_50)
scan_resDesired angular resolution (SickLMS1xx::SICK_LMS_1XX_SCAN_RES_25 or SickLMS1xx::SICK_LMS_1XX_SCAN_RES_50)
start_angleDesired start angle in (1/10000) deg (-450000 to 2250000)
stop_angleDesired stop angle in (1/10000) deg (-450000 to 2250000)
write_to_eepromIndicates whether the value should be written to EEPROM

Definition at line 1063 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_setSickScanDataFormat ( const sick_lms_1xx_scan_format_t  scan_format)
throw ( SickTimeoutException,
SickIOException,
SickThreadException,
SickErrorException
)
private

Sets the sick scan data format

Set device to output only range values

Definition at line 1794 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_setupConnection ( )
throw ( SickIOException,
SickTimeoutException
)
privatevirtual

Establish a TCP connection to the unit.

Setup the connection parameters and establish TCP connection!

Implements SickToolbox::SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >.

Definition at line 683 of file SickLMS1xx.cc.

std::string SickToolbox::SickLMS1xx::_sickScanDataFormatToString ( const sick_lms_1xx_scan_format_t  scan_format) const
private

Utility function for returning scan format as string.

Utility function for returning scan format as string

Parameters
dist_optDistance option corresponding to scan format
reflect_optReflectivity option corresponding to

Definition at line 2210 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_startMeasuring ( )
throw ( SickTimeoutException,
SickIOException
)
private

Tell the device to start measuring.

Start device measuring

Definition at line 1404 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_startStreamingMeasurements ( )
throw ( SickTimeoutException,
SickIOException
)
private

Start streaming measurements

Definition at line 1593 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_stopMeasuring ( )
throw ( SickTimeoutException,
SickIOException
)
private

Tell the device to start measuring.

Stop device measuring

Definition at line 1476 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_stopStreamingMeasurements ( const bool  disp_banner = true)
throw ( SickTimeoutException,
SickIOException
)
private

Stop Measurment Stream.

Stop streaming measurements

Definition at line 1660 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_teardownConnection ( )
throw (SickIOException
)
privatevirtual

Teardown TCP connection to Sick LMS 1xx.

Teardown the connection to the Sick LD

Implements SickToolbox::SickLIDAR< SickLMS1xxBufferMonitor, SickLMS1xxMessage >.

Definition at line 840 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_updateSickStatus ( )
throw ( SickTimeoutException,
SickIOException
)
private

Get the status of the Sick LMS 1xx.

Acquire the latest Sick LMS's status

Definition at line 852 of file SickLMS1xx.cc.

bool SickToolbox::SickLMS1xx::_validScanArea ( const int  start_angle,
const int  stop_angle 
) const
private

Utility function to ensure valid scan area.

Ensures a feasible scan area

Definition at line 2013 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::_writeToEEPROM ( )
throw ( SickTimeoutException,
SickIOException
)
private

Login as an authorized client.

Save configuration parameters to EEPROM

Definition at line 1330 of file SickLMS1xx.cc.

SickLMS1xx::sick_lms_1xx_scan_res_t SickToolbox::SickLMS1xx::DoubleToSickScanRes ( const double  scan_res) const

Convert double to corresponding sick_lms_1xx_scan_res_t.

Utility function for converting double to scan resolution

Definition at line 651 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::GetSickMeasurements ( unsigned int *const  range_1_vals,
unsigned int *const  range_2_vals,
unsigned int *const  reflect_1_vals,
unsigned int *const  reflect_2_vals,
unsigned int &  num_measurements,
unsigned int *const  dev_status = NULL 
)
throw ( SickIOException,
SickConfigException,
SickTimeoutException
)

Acquire multi-pulse sick range measurements.

Get the Sick Range Measurements

Parameters
range_1_valsA buffer to hold the range measurements
range_2_valsA buffer to hold the second pulse range measurements
refelct_1_valsA buffer to hold the frist pulse reflectivity
reflect_2_valsA buffer to hold the second pulse reflectivity

Definition at line 316 of file SickLMS1xx.cc.

sick_lms_1xx_scan_freq_t SickToolbox::SickLMS1xx::GetSickScanFreq ( ) const
throw (SickIOException
)

Gets the Sick LMS 1xx scan frequency.

Get the Sick LMS 1xx scan frequency

Returns
Sick LMS 1xx scan frequency {25,50} Hz

Definition at line 201 of file SickLMS1xx.cc.

sick_lms_1xx_scan_res_t SickToolbox::SickLMS1xx::GetSickScanRes ( ) const
throw (SickIOException
)

Gets the Sick LMS 1xx scan resolution.

Get the Sick LMS 1xx scan resolution

Returns
Sick LMS 1xx scan resolution {0.25 or 0.5} deg

Definition at line 216 of file SickLMS1xx.cc.

double SickToolbox::SickLMS1xx::GetSickStartAngle ( ) const
throw (SickIOException
)

Gets the Sick LMS 1xx scan area start angle [-45,270] deg.

Get the Sick LMS 1xx scan start angle

Returns
Sick LMS 1xx start angle as double

Definition at line 231 of file SickLMS1xx.cc.

double SickToolbox::SickLMS1xx::GetSickStopAngle ( ) const
throw (SickIOException
)

Gets the Sick LMS 1xx scan area start angle [-45,270] deg.

Get the Sick LMS 1xx scan stop angle

Returns
Sick LMS 1xx start angle as double

Definition at line 246 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::Initialize ( const bool  disp_banner = true)
throw ( SickIOException,
SickThreadException,
SickTimeoutException,
SickErrorException
)

Initializes the driver and syncs it with Sick LMS 1xx unit. Uses flash params.

Initializes the Sick LD unit (use scan areas defined in flash)

Definition at line 72 of file SickLMS1xx.cc.

SickLMS1xx::sick_lms_1xx_scan_freq_t SickToolbox::SickLMS1xx::IntToSickScanFreq ( const int  scan_freq) const

Convert integer to corresponding sick_lms_1xx_scan_freq_t.

Utility function for converting integer to scan frequency

Definition at line 619 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::SetSickScanDataFormat ( const sick_lms_1xx_scan_format_t  scan_format)
throw ( SickTimeoutException,
SickIOException,
SickThreadException,
SickErrorException
)

Sets the sick scan data format

Set device to output only range values

Definition at line 260 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::SetSickScanFreqAndRes ( const sick_lms_1xx_scan_freq_t  scan_freq,
const sick_lms_1xx_scan_res_t  scan_res 
)
throw ( SickTimeoutException,
SickIOException,
SickErrorException
)

Sets the Sick LMS 1xx scan frequency and resolution.

Sets the Sick LMS 1xx scan frequency and scan resolution

Parameters
scan_freqDesired scan frequency (e.g. SickLMS1xx::SICK_LMS_1XX_SCAN_FREQ_50)
scan_resDesired scan angular resolution (e.g. SickLMS1xx::SICK_LMS_1XX_SCAN_RES_50)
write_to_eepromWrite the configuration to EEPROM

Definition at line 148 of file SickLMS1xx.cc.

int SickToolbox::SickLMS1xx::SickScanFreqToInt ( const sick_lms_1xx_scan_freq_t  scan_freq) const

Convert sick_lms_1xx_scan_freq_t to corresponding integer.

Utility function for converting scan frequency to integer

Definition at line 635 of file SickLMS1xx.cc.

double SickToolbox::SickLMS1xx::SickScanResToDouble ( const sick_lms_1xx_scan_res_t  scan_res) const

Convert sick_lms_1xx_scan_res_t to corresponding double.

Utility function for converting scan resolution to double

Definition at line 667 of file SickLMS1xx.cc.

void SickToolbox::SickLMS1xx::Uninitialize ( const bool  disp_banner = true)
throw ( SickIOException,
SickTimeoutException,
SickErrorException,
SickThreadException
)

Tear down the connection between the host and the Sick LD.

Uninitializes the Sick LD unit

Definition at line 539 of file SickLMS1xx.cc.

Member Data Documentation

sick_lms_1xx_status_t SickToolbox::SickLMS1xx::_sick_device_status
private

Sick LMS 1xx configuration struct

Definition at line 203 of file SickLMS1xx.hh.

struct sockaddr_in SickToolbox::SickLMS1xx::_sick_inet_address_info
private

Sick LMS 1xx socket address struct

Definition at line 194 of file SickLMS1xx.hh.

std::string SickToolbox::SickLMS1xx::_sick_ip_address
private

The Sick LMS 1xx IP address

Definition at line 188 of file SickLMS1xx.hh.

sick_lms_1xx_scan_config_t SickToolbox::SickLMS1xx::_sick_scan_config
private

Sick LMS 1xx configuration struct

Definition at line 197 of file SickLMS1xx.hh.

sick_lms_1xx_scan_format_t SickToolbox::SickLMS1xx::_sick_scan_format
private

Sick LMS 1xx current scan data format

Definition at line 200 of file SickLMS1xx.hh.

bool SickToolbox::SickLMS1xx::_sick_streaming
private

Sick LMS 1xx streaming status

Definition at line 209 of file SickLMS1xx.hh.

uint16_t SickToolbox::SickLMS1xx::_sick_tcp_port
private

The Sick LMS 1xx TCP port number

Definition at line 191 of file SickLMS1xx.hh.

bool SickToolbox::SickLMS1xx::_sick_temp_safe
private

Sick LMS 1xx temperature status

Definition at line 206 of file SickLMS1xx.hh.

const int SickToolbox::SickLMS1xx::SICK_LMS_1XX_MAX_NUM_MEASUREMENTS = 1082
static

LMS 1xx max number of measurements.

Definition at line 54 of file SickLMS1xx.hh.


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


sicktoolbox
Author(s): Jason Derenick , Thomas Miller
autogenerated on Tue Sep 10 2019 03:37:34