A general class for interfacing w/ SickPLS laser range finders. More...
#include <SickPLS.hh>
Classes | |
struct | sick_pls_baud_status_tag |
A structure for aggregating the data that collectively define the baud config. More... | |
struct | sick_pls_operating_status_tag |
A structure for aggregating the data that collectively defines the operating status of the device. More... | |
struct | sick_pls_scan_profile_b0_tag |
A structure for aggregating the data that define a scan profile obtained from reply B0 (See page 49 Telegram listing) More... | |
Public Types | |
typedef struct SickToolbox::SickPLS::sick_pls_baud_status_tag | sick_pls_baud_status_t |
Adopt c-style convention. | |
enum | sick_pls_baud_t { SICK_BAUD_9600 = 0x42, SICK_BAUD_19200 = 0x41, SICK_BAUD_38400 = 0x40, SICK_BAUD_500K = 0x48, SICK_BAUD_UNKNOWN = 0xFF } |
Defines available Sick PLS baud rates. More... | |
enum | sick_pls_measuring_units_t { SICK_MEASURING_UNITS_CM = 0x00, SICK_MEASURING_UNITS_UNKNOWN = 0xFF } |
Defines the available Sick PLS measured value units. More... | |
enum | sick_pls_operating_mode_t { SICK_OP_MODE_INSTALLATION = 0x00, SICK_OP_MODE_DIAGNOSTIC = 0x10, SICK_OP_MODE_MONITOR_STREAM_MIN_VALUE_FOR_EACH_SEGMENT = 0x20, SICK_OP_MODE_MONITOR_TRIGGER_MIN_VALUE_ON_OBJECT = 0x21, SICK_OP_MODE_MONITOR_STREAM_MIN_VERT_DIST_TO_OBJECT = 0x22, SICK_OP_MODE_MONITOR_TRIGGER_MIN_VERT_DIST_TO_OBJECT = 0x23, SICK_OP_MODE_MONITOR_STREAM_VALUES = 0x24, SICK_OP_MODE_MONITOR_REQUEST_VALUES = 0x25, SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES = 0x26, SICK_OP_MODE_MONITOR_STREAM_VALUES_SUBRANGE = 0x27, SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES_SUBRANGE = 0x28, SICK_OP_MODE_MONITOR_STREAM_VALUES_WITH_FIELDS = 0x29, SICK_OP_MODE_MONITOR_STREAM_VALUES_FROM_PARTIAL_SCAN = 0x2A, SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT_FROM_PARTIAL_SCAN = 0x2B, SICK_OP_MODE_MONITOR_STREAM_MIN_VALUES_FOR_EACH_SEGMENT_SUBRANGE = 0x2C, SICK_OP_MODE_MONITOR_NAVIGATION = 0x2E, SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT = 0x50, SICK_OP_MODE_UNKNOWN = 0xFF } |
Defines the operating modes supported by Sick PLS. See page 41 of the PLS telegram manual for additional descriptions of these modes. More... | |
typedef struct SickToolbox::SickPLS::sick_pls_operating_status_tag | sick_pls_operating_status_t |
Adopt c-style convention. | |
enum | sick_pls_scan_angle_t { SICK_SCAN_ANGLE_180 = 180, SICK_SCAN_ANGLE_UNKNOWN = 0xFF } |
Defines the scan angle for the Sick PLS. More... | |
typedef struct SickToolbox::SickPLS::sick_pls_scan_profile_b0_tag | sick_pls_scan_profile_b0_t |
Adopt c-style convention. | |
enum | sick_pls_scan_resolution_t { SICK_SCAN_RESOLUTION_50 = 50, SICK_SCAN_RESOLUTION_UNKNOWN = 0xFF } |
Defines the available resolution settings for the Sick PLS. More... | |
enum | sick_pls_status_t { SICK_STATUS_OK = 0x00, SICK_STATUS_ERROR = 0x01, SICK_STATUS_UNKNOWN = 0xFF } |
Defines the status of the Sick PLS unit. More... | |
Public Member Functions | |
std::string | GetSickDevicePath () const |
Gets the Sick PLS device path. | |
SickPLS::sick_pls_measuring_units_t | GetSickMeasuringUnits () const throw ( SickConfigException ) |
Gets the current Sick PLS measuring units. | |
sick_pls_operating_mode_t | GetSickOperatingMode () const throw ( SickConfigException ) |
Gets the current Sick PLS operating mode. | |
void | GetSickScan (unsigned int *const measurement_values, unsigned int &num_measurement_values) throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Returns the most recent measured values obtained by the Sick PLS. | |
double | GetSickScanAngle () const throw ( SickConfigException ) |
Gets the current scan angle of the device. | |
double | GetSickScanResolution () const throw ( SickConfigException ) |
Gets the current angular resolution. | |
sick_pls_status_t | GetSickStatus () throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) |
std::string | GetSickStatusAsString () const |
Acquire the Sick PLS's status as a printable string. | |
bool | Initialize (const sick_pls_baud_t desired_baud_rate) throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Attempts to initialize the Sick PLS and then sets communication at at the given baud rate. | |
void | ResetSick () throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) |
Reset the Sick PLS active field values NOTE: Considered successful if the PLS ready message is received. | |
SickPLS (const std::string sick_device_path) | |
Primary constructor. | |
void | Uninitialize () throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) |
Uninitializes the PLS by putting it in a mode where it stops streaming data, and returns it to the default baud rate (specified in the header). | |
~SickPLS () | |
Destructor. | |
Static Public Member Functions | |
static sick_pls_scan_resolution_t | DoubleToSickScanResolution (const double scan_resolution_double) |
Converts double to corresponding Sick PLS scan resolution. | |
static sick_pls_baud_t | IntToSickBaud (const int baud_int) |
Converts integer to corresponding Sick PLS baud. | |
static sick_pls_scan_angle_t | IntToSickScanAngle (const int scan_angle_int) |
Converts integer to corresponding Sick PLS scan angle. | |
static sick_pls_scan_resolution_t | IntToSickScanResolution (const int scan_resolution_int) |
Converts integer to corresponding Sick PLS scan resolution. | |
static std::string | SickBaudToString (const sick_pls_baud_t baud_rate) |
Converts Sick PLS baud to a corresponding string. | |
static std::string | SickMeasuringUnitsToString (const sick_pls_measuring_units_t sick_units) |
Converts the Sick PLS measurement units to a corresponding string. | |
static std::string | SickOperatingModeToString (const sick_pls_operating_mode_t sick_operating_mode) |
Converts the Sick operating mode to a corresponding string. | |
static std::string | SickStatusToString (const sick_pls_status_t sick_status) |
Converts the Sick PLS status code to a string. | |
static sick_pls_baud_t | StringToSickBaud (const std::string baud_str) |
Converts string to corresponding Sick PLS baud. | |
Static Public Attributes | |
static const uint16_t | SICK_MAX_NUM_MEASUREMENTS = 721 |
Maximum number of measurements returned by the Sick PLS. | |
Protected Member Functions | |
sick_pls_baud_t | _baudToSickBaud (const int baud_rate) const |
Converts a termios baud to an equivalent Sick baud. | |
void | _extractSickMeasurementValues (const uint8_t *const byte_sequence, const uint16_t num_measurements, uint16_t *const measured_values) const |
Extracts the measured values (w/ flags) that were returned by the device. | |
void | _flushTerminalBuffer () throw ( SickThreadException ) |
Flushes terminal I/O buffers. | |
void | _getSickErrors (unsigned int *const num_sick_errors=NULL, uint8_t *const error_type_buffer=NULL, uint8_t *const error_num_buffer=NULL) throw ( SickTimeoutException, SickIOException, SickThreadException ) |
Obtains any error codes from the Sick PLS. | |
void | _parseSickScanProfileB0 (const uint8_t *const src_buffer, sick_pls_scan_profile_b0_t &sick_scan_profile) const |
Parses a byte sequence into a scan profile corresponding to message B0. | |
void | _sendMessageAndGetReply (const SickPLSMessage &sick_send_message, SickPLSMessage &sick_recv_message, const unsigned int timeout_value, const unsigned int num_tries) throw ( SickIOException, SickThreadException, SickTimeoutException ) |
Sends a message and searches for the corresponding reply. | |
void | _sendMessageAndGetReply (const SickPLSMessage &sick_send_message, SickPLSMessage &sick_recv_message, const uint8_t reply_code, const unsigned int timeout_value, const unsigned int num_tries) throw ( SickIOException, SickThreadException, SickTimeoutException ) |
Sends a message and searches for the reply with given reply code. | |
void | _setSessionBaud (const sick_pls_baud_t baud_rate) throw ( SickIOException, SickThreadException, SickTimeoutException ) |
Sets the baud rate for the current communication session. | |
void | _setSickOpModeDiagnostic () throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Sets the device to diagnostic mode. | |
void | _setSickOpModeInstallation () throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Sets the device to installation mode. | |
void | _setSickOpModeMonitorRequestValues () throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Sets the device to monitor mode and tells it to send values only upon request. | |
void | _setSickOpModeMonitorStreamValues () throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Sets the device to monitor mode and tells it to stream measured values. | |
void | _setTerminalBaud (const sick_pls_baud_t sick_baud) throw ( SickIOException, SickThreadException ) |
Sets the local terminal baud rate. | |
void | _setupConnection () throw ( SickIOException, SickThreadException ) |
Attempts to open a I/O stream using the device path given at object instantiation. | |
void | _switchSickOperatingMode (const uint8_t sick_mode, const uint8_t *const mode_params=NULL) throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Attempts to switch the operating mode of the Sick PLS. | |
void | _teardownConnection () throw ( SickIOException ) |
Closes the data connection associated with the device. | |
bool | _testSickBaud (const sick_pls_baud_t baud_rate) throw ( SickIOException, SickThreadException ) |
Attempts to detect whether the PLS is operating at the given baud rate. | |
bool | _validSickScanAngle (const sick_pls_scan_angle_t sick_scan_angle) const |
Indicates whether the given scan angle is defined. | |
bool | _validSickScanResolution (const sick_pls_scan_resolution_t sick_scan_resolution) const |
Indicates whether the given scan resolution is defined. | |
Protected Attributes | |
sick_pls_baud_t | _curr_session_baud |
sick_pls_baud_t | _desired_session_baud |
struct termios | _old_term |
sick_pls_baud_status_t | _sick_baud_status |
std::string | _sick_device_path |
sick_pls_operating_status_t | _sick_operating_status |
A general class for interfacing w/ SickPLS laser range finders.
This class implements the basic telegram protocol for SickPLS range finders. It allows the setting of such parameters as angular resolution, fov, etc...
Definition at line 50 of file SickPLS.hh.
Adopt c-style convention.
Adopt c-style convention.
Adopt c-style convention.
Defines available Sick PLS baud rates.
SICK_BAUD_9600 |
9600 baud |
SICK_BAUD_19200 |
19200 baud |
SICK_BAUD_38400 |
38400 baud |
SICK_BAUD_500K |
500000 baud |
SICK_BAUD_UNKNOWN |
Unknown baud rate. |
Definition at line 134 of file SickPLS.hh.
Defines the available Sick PLS measured value units.
SICK_MEASURING_UNITS_CM |
Measured values are in centimeters. |
SICK_MEASURING_UNITS_UNKNOWN |
Unknown units. |
Definition at line 84 of file SickPLS.hh.
Defines the operating modes supported by Sick PLS. See page 41 of the PLS telegram manual for additional descriptions of these modes.
Definition at line 106 of file SickPLS.hh.
Defines the scan angle for the Sick PLS.
SICK_SCAN_ANGLE_180 |
Scanning angle of 180 degrees. PLS only does 180 |
SICK_SCAN_ANGLE_UNKNOWN |
Unknown scanning angle. |
Definition at line 64 of file SickPLS.hh.
Defines the available resolution settings for the Sick PLS.
SICK_SCAN_RESOLUTION_50 |
0.50 degree angular resolution PLS only does 0.5 deg angular resolution |
SICK_SCAN_RESOLUTION_UNKNOWN |
Unknown angular resolution. |
Definition at line 74 of file SickPLS.hh.
Defines the status of the Sick PLS unit.
SICK_STATUS_OK |
PLS is OK. |
SICK_STATUS_ERROR |
PLS has encountered an error. |
SICK_STATUS_UNKNOWN |
Unknown PLS status. |
Definition at line 95 of file SickPLS.hh.
SickToolbox::SickPLS::SickPLS | ( | const std::string | sick_device_path | ) |
Primary constructor.
Constructor
sick_device_path | The path of the device |
Definition at line 46 of file SickPLS.cc.
sick_pls_baud_t SickToolbox::SickPLS::_baudToSickBaud | ( | const int | baud_rate | ) | const [protected] |
Converts a termios baud to an equivalent Sick baud.
Given a baud rate as an integer, gets a PLS baud rate command.
baud_rate | The baud rate to be converted to a Sick PLS baud |
Definition at line 2000 of file SickPLS.cc.
void SickToolbox::SickPLS::_extractSickMeasurementValues | ( | const uint8_t *const | byte_sequence, |
const uint16_t | num_measurements, | ||
uint16_t *const | measured_values | ||
) | const [protected] |
Extracts the measured values (w/ flags) that were returned by the device.
Acquires the bit mask to extract the field bit values returned with each range measurement
*byte_sequence | The byte sequence holding the current measured values |
num_measurements | The number of measurements given in the byte sequence |
*measured_values | A buffer to hold the extracted measured values |
*field_a_values | Stores the Field A values associated with the given measurements (Default: NULL => Not wanted) |
*field_b_values | Stores the Field B values associated with the given measurements (Default: NULL => Not wanted) |
*field_c_values | Stores the Field C values associated with the given measurements (Default: NULL => Not wanted) |
Definition at line 1946 of file SickPLS.cc.
void SickToolbox::SickPLS::_flushTerminalBuffer | ( | ) | throw ( SickThreadException ) [protected] |
Flushes terminal I/O buffers.
Flushes the terminal I/O buffers
Definition at line 916 of file SickPLS.cc.
void SickToolbox::SickPLS::_getSickErrors | ( | unsigned int *const | num_sick_errors = NULL , |
uint8_t *const | error_type_buffer = NULL , |
||
uint8_t *const | error_num_buffer = NULL |
||
) | throw ( SickTimeoutException, SickIOException, SickThreadException ) [protected] |
Obtains any error codes from the Sick PLS.
Gets the error status of the Sick PLS
Definition at line 1339 of file SickPLS.cc.
void SickToolbox::SickPLS::_parseSickScanProfileB0 | ( | const uint8_t *const | src_buffer, |
sick_pls_scan_profile_b0_t & | sick_scan_profile | ||
) | const [protected] |
Parses a byte sequence into a scan profile corresponding to message B0.
Parses the scan profile returned w/ message B0
*src_buffer | The byte sequence to be parsed |
&sick_scan_profile | The returned scan profile for the current round of measurements |
Definition at line 1914 of file SickPLS.cc.
void SickToolbox::SickPLS::_sendMessageAndGetReply | ( | const SickPLSMessage & | send_message, |
SickPLSMessage & | recv_message, | ||
const unsigned int | timeout_value, | ||
const unsigned int | num_tries | ||
) | throw ( SickIOException, SickThreadException, SickTimeoutException ) [protected] |
Sends a message and searches for the corresponding reply.
Sends a message to the PLS and get the expected reply using th 0x80 rule.
&send_message | The message to be sent to the Sick PLS unit |
&recv_message | The expected message reply from the Sick PLS |
timeout_value | The epoch to wait before considering a sent frame lost (in usecs) |
num_tries | The number of times to try and transmit the message before quitting |
NOTE: Uses the 0x80 response code rule for looking for the response message
Definition at line 962 of file SickPLS.cc.
void SickToolbox::SickPLS::_sendMessageAndGetReply | ( | const SickPLSMessage & | send_message, |
SickPLSMessage & | recv_message, | ||
const uint8_t | reply_code, | ||
const unsigned int | timeout_value, | ||
const unsigned int | num_tries | ||
) | throw ( SickIOException, SickThreadException, SickTimeoutException ) [protected] |
Sends a message and searches for the reply with given reply code.
Sends a message to the PLS and get the expected reply using th 0x80 rule.
&send_message | The message to be sent to the Sick PLS unit |
&recv_message | The expected message reply from the Sick PLS |
reply_code | The reply code associated with the expected messgage |
timeout_value | The epoch to wait before considering a sent frame lost (in usecs) |
num_tries | The number of times to send the message in the event the PLS fails to reply |
Definition at line 1021 of file SickPLS.cc.
void SickToolbox::SickPLS::_setSessionBaud | ( | const sick_pls_baud_t | baud_rate | ) | throw ( SickIOException, SickThreadException, SickTimeoutException ) [protected] |
Sets the baud rate for the current communication session.
Sets the baud rate for communication with the PLS.
baud_rate | The desired baud rate |
Definition at line 1076 of file SickPLS.cc.
void SickToolbox::SickPLS::_setSickOpModeDiagnostic | ( | ) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) [protected] |
Sets the device to diagnostic mode.
Switch Sick PLS to diagnostic mode
Definition at line 1492 of file SickPLS.cc.
void SickToolbox::SickPLS::_setSickOpModeInstallation | ( | ) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) [protected] |
Sets the device to installation mode.
Switch Sick PLS to installation mode
Definition at line 1429 of file SickPLS.cc.
void SickToolbox::SickPLS::_setSickOpModeMonitorRequestValues | ( | ) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) [protected] |
Sets the device to monitor mode and tells it to send values only upon request.
Switch Sick PLS to monitor mode (request range data)
Definition at line 1557 of file SickPLS.cc.
void SickToolbox::SickPLS::_setSickOpModeMonitorStreamValues | ( | ) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) [protected] |
Sets the device to monitor mode and tells it to stream measured values.
Switch Sick PLS to monitor mode (stream range)
Definition at line 1618 of file SickPLS.cc.
void SickToolbox::SickPLS::_setTerminalBaud | ( | const sick_pls_baud_t | baud_rate | ) | throw ( SickIOException, SickThreadException ) [protected] |
Sets the local terminal baud rate.
Changes the terminal's baud rate.
baud_rate | The desired terminal baud rate |
Definition at line 1225 of file SickPLS.cc.
void SickToolbox::SickPLS::_setupConnection | ( | ) | throw ( SickIOException, SickThreadException ) [protected, virtual] |
Attempts to open a I/O stream using the device path given at object instantiation.
Opens the terminal for serial communication.
Implements SickToolbox::SickLIDAR< SickPLSBufferMonitor, SickPLSMessage >.
Definition at line 841 of file SickPLS.cc.
void SickToolbox::SickPLS::_switchSickOperatingMode | ( | const uint8_t | sick_mode, |
const uint8_t *const | mode_params = NULL |
||
) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) [protected] |
Attempts to switch the operating mode of the Sick PLS.
Switches the operating mode of the PLS.
sick_mode | The desired operating mode |
mode_params | Additional parameters required to set the new operating mode |
Definition at line 1686 of file SickPLS.cc.
void SickToolbox::SickPLS::_teardownConnection | ( | ) | throw ( SickIOException ) [protected, virtual] |
Closes the data connection associated with the device.
Closes the serial communication terminal.
Implements SickToolbox::SickLIDAR< SickPLSBufferMonitor, SickPLSMessage >.
Definition at line 890 of file SickPLS.cc.
bool SickToolbox::SickPLS::_testSickBaud | ( | const sick_pls_baud_t | baud_rate | ) | throw ( SickIOException, SickThreadException ) [protected] |
Attempts to detect whether the PLS is operating at the given baud rate.
Tests communication wit the PLS at a particular baud rate.
baud_rate | The baud rate to use when "pinging" the Sick PLS |
Definition at line 1153 of file SickPLS.cc.
bool SickToolbox::SickPLS::_validSickScanAngle | ( | const sick_pls_scan_angle_t | sick_scan_angle | ) | const [protected] |
Indicates whether the given scan angle is defined.
Indicates whether the given scan angle is defined
sick_scan_angle | The scan angle in question |
Definition at line 1961 of file SickPLS.cc.
bool SickToolbox::SickPLS::_validSickScanResolution | ( | const sick_pls_scan_resolution_t | sick_scan_resolution | ) | const [protected] |
Indicates whether the given scan resolution is defined.
Indicates whether the given scan resolution is defined
sick_scan_resolution | The scan resolution in question |
Definition at line 1979 of file SickPLS.cc.
sick_pls_scan_resolution_t SickToolbox::SickPLS::DoubleToSickScanResolution | ( | const double | scan_resolution_double | ) | [static] |
Converts double to corresponding Sick PLS scan resolution.
A utility function for converting doubles to pls_sick_scan_resolution_t
scan_resolution_double | Scan resolution as a double (e.g. 0.25,0.5,1.0) |
Definition at line 682 of file SickPLS.cc.
std::string SickToolbox::SickPLS::GetSickDevicePath | ( | ) | const |
Gets the Sick PLS device path.
Gets the Sick PLS device path
Definition at line 328 of file SickPLS.cc.
sick_pls_measuring_units_t SickToolbox::SickPLS::GetSickMeasuringUnits | ( | ) | const throw ( SickConfigException ) |
Gets the current Sick PLS measuring units.
Get the current measurement units of the device
Definition at line 376 of file SickPLS.cc.
sick_pls_operating_mode_t SickToolbox::SickPLS::GetSickOperatingMode | ( | ) | const throw ( SickConfigException ) |
Gets the current Sick PLS operating mode.
Get the current Sick PLS operating mode
Definition at line 392 of file SickPLS.cc.
void SickToolbox::SickPLS::GetSickScan | ( | unsigned int *const | measurement_values, |
unsigned int & | num_measurement_values | ||
) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Returns the most recent measured values obtained by the Sick PLS.
Gets measurement data from the Sick. NOTE: Data can be either range or reflectivity given the Sick mode.
*measurement_values | Destination buffer for holding the current round of measured values |
&num_measurement_values | Number of values stored in measurement_values |
*sick_field_a_values | Stores the Field A values associated with the given scan (Default: NULL => Not wanted) |
*sick_field_b_values | Stores the Field B values associated with the given scan (Default: NULL => Not wanted) |
*sick_field_c_values | Stores the Field C values associated with the given scan (Default: NULL => Not wanted) |
*sick_telegram_index | The telegram index assigned to the message (modulo: 256) (Default: NULL => Not wanted) |
*sick_real_time_scan_index | The real time scan index for the latest message (module 256) (Default: NULL => Not wanted) |
NOTE: Calling this function will return either range or reflectivity measurements depending upon the current measuring mode of the device.
NOTE: Real-time scan indices must be enabled by setting the corresponding availability of the Sick PLS for this value to be populated.
Definition at line 424 of file SickPLS.cc.
double SickToolbox::SickPLS::GetSickScanAngle | ( | ) | const throw ( SickConfigException ) |
Gets the current scan angle of the device.
Gets the scan angle currently being used by the device
Definition at line 338 of file SickPLS.cc.
double SickToolbox::SickPLS::GetSickScanResolution | ( | ) | const throw ( SickConfigException ) |
Gets the current angular resolution.
Gets the scan resolution currently being used by the device
Definition at line 356 of file SickPLS.cc.
sick_pls_status_t SickToolbox::SickPLS::GetSickStatus | ( | ) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) |
Acquire the Sick PLS status
std::string SickToolbox::SickPLS::GetSickStatusAsString | ( | ) | const |
Acquire the Sick PLS's status as a printable string.
Get Sick status as a string
Definition at line 611 of file SickPLS.cc.
bool SickToolbox::SickPLS::Initialize | ( | const sick_pls_baud_t | desired_baud_rate | ) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException) |
Attempts to initialize the Sick PLS and then sets communication at at the given baud rate.
Initializes the Sick
desired_baud_rate | Desired session baud rate |
Definition at line 99 of file SickPLS.cc.
sick_pls_baud_t SickToolbox::SickPLS::IntToSickBaud | ( | const int | baud_int | ) | [static] |
Converts integer to corresponding Sick PLS baud.
A utility function for converting integers to pls_baud_t
baud_str | Baud rate as integer (e.g. 9600,19200,38400,500000) |
Definition at line 715 of file SickPLS.cc.
sick_pls_scan_angle_t SickToolbox::SickPLS::IntToSickScanAngle | ( | const int | scan_angle_int | ) | [static] |
Converts integer to corresponding Sick PLS scan angle.
A utility function for converting integers to pls_sick_scan_angle_t
scan_angle_int | Scan angle (FOV) as an integer (e.g. 90,100,180) |
Definition at line 648 of file SickPLS.cc.
sick_pls_scan_resolution_t SickToolbox::SickPLS::IntToSickScanResolution | ( | const int | scan_resolution_int | ) | [static] |
Converts integer to corresponding Sick PLS scan resolution.
A utility function for converting ints to pls_sick_scan_resolution_t
scan_resolution_int | Scan resolution as an integer (e.g. 25,50,100) |
Definition at line 665 of file SickPLS.cc.
void SickToolbox::SickPLS::ResetSick | ( | ) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) |
Reset the Sick PLS active field values NOTE: Considered successful if the PLS ready message is received.
Resets Sick PLS field values
Definition at line 525 of file SickPLS.cc.
std::string SickToolbox::SickPLS::SickBaudToString | ( | const sick_pls_baud_t | baud_rate | ) | [static] |
Converts Sick PLS baud to a corresponding string.
Converts the given bad, returns a string representing that baud rate.
baud_rate | The baud rate to be represented as a string |
Definition at line 692 of file SickPLS.cc.
std::string SickToolbox::SickPLS::SickMeasuringUnitsToString | ( | const sick_pls_measuring_units_t | sick_units | ) | [static] |
Converts the Sick PLS measurement units to a corresponding string.
Converts the PLS's measuring units to a corresponding string
sick_units | The measuring units |
Definition at line 824 of file SickPLS.cc.
std::string SickToolbox::SickPLS::SickOperatingModeToString | ( | const sick_pls_operating_mode_t | sick_operating_mode | ) | [static] |
Converts the Sick operating mode to a corresponding string.
Converts the PLS's measuring mode to a corresponding string
sick_operating_mode | The Sick operating mode |
Definition at line 772 of file SickPLS.cc.
std::string SickToolbox::SickPLS::SickStatusToString | ( | const sick_pls_status_t | sick_status | ) | [static] |
Converts the Sick PLS status code to a string.
Converts the PLS's status to a corresponding string
sick_status | The device status |
Definition at line 754 of file SickPLS.cc.
sick_pls_baud_t SickToolbox::SickPLS::StringToSickBaud | ( | const std::string | baud_str | ) | [static] |
Converts string to corresponding Sick PLS baud.
A utility function for converting baud strings to pls_baud_t
baud_str | Baud rate as string (e.g. "9600","19200","38400","500000") |
Definition at line 738 of file SickPLS.cc.
void SickToolbox::SickPLS::Uninitialize | ( | ) | throw ( SickConfigException, SickTimeoutException, SickIOException, SickThreadException ) |
Uninitializes the PLS by putting it in a mode where it stops streaming data, and returns it to the default baud rate (specified in the header).
Uninitializes the Sick
Definition at line 253 of file SickPLS.cc.
The baud rate at which to communicate with the Sick
Definition at line 282 of file SickPLS.hh.
The desired baud rate for communicating w/ the Sick
Definition at line 285 of file SickPLS.hh.
struct termios SickToolbox::SickPLS::_old_term [protected] |
Stores information about the original terminal settings
Definition at line 297 of file SickPLS.hh.
The baud configuration of the device
Definition at line 293 of file SickPLS.hh.
std::string SickToolbox::SickPLS::_sick_device_path [protected] |
A path to the device at which the sick can be accessed.
Definition at line 279 of file SickPLS.hh.
The operating parameters of the device
Definition at line 289 of file SickPLS.hh.
const uint16_t SickToolbox::SickPLS::SICK_MAX_NUM_MEASUREMENTS = 721 [static] |
Maximum number of measurements returned by the Sick PLS.
Define the maximum number of measurements
Definition at line 57 of file SickPLS.hh.