Classes | Public Types | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
SickToolbox::SickLD Class Reference

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

#include <SickLD.hh>

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

List of all members.

Classes

struct  sick_ld_config_ethernet_tag
 A structure to aggregate the data used to configure the Sick LD unit for Ethernet. More...
struct  sick_ld_config_global_tag
 A structure to aggregate the data used to configure the Sick LD global parameter values. More...
struct  sick_ld_config_sector_tag
 A structure to aggregate data used to define the Sick LD's sector configuration. More...
struct  sick_ld_identity_tag
 A structure to aggregate the fields that collectively define the identity of a Sick LD unit. More...
struct  sick_ld_scan_profile_tag
 A structure to aggregate the fields that collectively define the profile of a single scan acquired from the Sick LD unit. More...
struct  sick_ld_sector_data_tag
 A structure to aggregate the fields that collectively define a sector in the scan area of the Sick LD unit. More...

Public Types

typedef struct
SickToolbox::SickLD::sick_ld_config_ethernet_tag 
sick_ld_config_ethernet_t
 Adopt c-style convention.
typedef struct
SickToolbox::SickLD::sick_ld_config_global_tag 
sick_ld_config_global_t
 Adopt c-style convention.
typedef struct
SickToolbox::SickLD::sick_ld_config_sector_tag 
sick_ld_config_sector_t
 Adopt c-style convention.
typedef struct
SickToolbox::SickLD::sick_ld_identity_tag 
sick_ld_identity_t
 Adopt c-style convention.
typedef struct
SickToolbox::SickLD::sick_ld_scan_profile_tag 
sick_ld_scan_profile_t
 Adopt c-style convention.
typedef struct
SickToolbox::SickLD::sick_ld_sector_data_tag 
sick_ld_sector_data_t
 Adopt c-style convention.

Public Member Functions

void DisableNearfieldSuppression () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Disables nearfield suppressive filtering.
void EnableNearfieldSuppression () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Enables nearfield suppressive filtering.
std::string GetSickAppSoftwareName () const
 Acquire the Sick LD's application software name.
std::string GetSickAppSoftwarePartNumber () const
 Acquire the Sick LD's application software part number.
std::string GetSickAppSoftwareVersionNumber () const
 Acquire the Sick LD's application software version number.
std::string GetSickEDMSerialNumber () const
 Acquire the Sick LD's EDM serial number.
std::string GetSickEthernetConfigAsString () const
 Acquire the Sick LD's global config as a printable string.
std::string GetSickFirmwareName () const
 Acquire the Sick LD's firmware number.
std::string GetSickFirmwarePartNumber () const
 Acquire the Sick LD's firmware part number.
std::string GetSickFirmwareVersion () const
 Acquire the Sick LD's firmware version.
std::string GetSickGatewayIPAddress () const
 Acquire the IP address of the Sick gateway.
std::string GetSickGlobalConfigAsString () const
 Acquire the Sick LD's global config as a printable string.
std::string GetSickIdentityAsString () const
 Acquire the Sick LD's identity as a printable string.
std::string GetSickIPAddress () const
 Acquire the current IP address of the Sick.
void GetSickMeasurements (double *const range_measurements, unsigned int *const echo_measurements=NULL, unsigned int *const num_measurements=NULL, unsigned int *const sector_ids=NULL, unsigned int *const sector_data_offsets=NULL, double *const sector_step_angles=NULL, double *const sector_start_angles=NULL, double *const sector_stop_angles=NULL, unsigned int *const sector_start_timestamps=NULL, unsigned int *const sector_stop_timestamps=NULL) throw ( SickErrorException, SickIOException, SickTimeoutException, SickConfigException )
 Acquires measurements and corresponding sector data from the Sick LD.
unsigned int GetSickMotorSpeed () const
 Acquire the Sick LD's current motor speed in Hz.
std::string GetSickName () const
 Acquire the Sick LD's name.
unsigned int GetSickNumActiveSectors () const
 Acquire the number of sectors that are measuring.
std::string GetSickPartNumber () const
 Acquire the Sick LD's part number.
double GetSickScanArea () const
 Computes the active area over all measuring sectors.
double GetSickScanResolution () const
 Acquire the Sick LD's current scan resolution.
std::string GetSickSectorConfigAsString () const
 Acquire the Sick LD's sector config as a printable string.
unsigned int GetSickSensorID () const
 Acquire the Sick LD's sensor ID.
std::string GetSickSerialNumber () const
 Acquire the Sick LD's serial number.
void GetSickSignals (uint8_t &sick_signal_flags) throw ( SickIOException, SickTimeoutException )
 Gets the Sick LD signal LED's and switching outputs.
void GetSickStatus (unsigned int &sick_sensor_mode, unsigned int &sick_motor_mode) throw ( SickIOException, SickTimeoutException )
 Acquires the status of the Sick from the device.
std::string GetSickStatusAsString () const
 Acquire the Sick LD's status as a printable string.
std::string GetSickSubnetMask () const
 Acquire the subnet mask for the Sick.
void GetSickTime (uint16_t &sick_time) throw ( SickIOException, SickTimeoutException, SickErrorException )
 Gets the internal clock time of the Sick LD unit.
std::string GetSickVersion () const
 Acquire the Sick LD's version number.
void Initialize () throw ( SickIOException, SickThreadException, SickTimeoutException, SickErrorException )
 Initializes the driver and syncs it with Sick LD unit. Uses sector config given in flash.
void PrintSickEthernetConfig () const
 Print the Sick LD's Ethernet configuration.
void PrintSickGlobalConfig () const
 Print the Sick LD's global configuration.
void PrintSickIdentity () const
 Print the parameters comprising the Sick LD's identity.
void PrintSickSectorConfig () const
 Print the Sick LD's sector configuration.
void PrintSickStatus () const
 Print the status of the Sick LD.
void ResetSick (const unsigned int reset_level=SICK_WORK_SERV_RESET_INIT_CPU) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException )
 Resets the device according to the given reset level.
void SetSickGlobalParamsAndScanAreas (const unsigned int sick_motor_speed, const double sick_step_angle, const double *const active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors) throw ( SickTimeoutException, SickIOException, SickConfigException, SickErrorException )
 Attempts to set the scan resolution and active sectors/scan areas for the device (in flash)
void SetSickMotorSpeed (const unsigned int sick_motor_speed) throw ( SickErrorException, SickTimeoutException, SickIOException )
void SetSickScanAreas (const double *const active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors) throw ( SickTimeoutException, SickIOException, SickConfigException, SickErrorException )
 Attempts to set the active scan areas for the device (in flash)
void SetSickScanResolution (const double sick_step_angle) throw ( SickTimeoutException, SickIOException, SickConfigException )
 Attempts to set a new scan resolution for the device (in flash) while retaining the previously defined active scan areas.
void SetSickSensorID (const unsigned int sick_sensor_id) throw ( SickErrorException, SickTimeoutException, SickIOException )
 Attempts to set a new sensor ID for the device (in flash)
void SetSickSignals (const uint8_t sick_signal_flags=DEFAULT_SICK_SIGNAL_SET) throw ( SickIOException, SickTimeoutException, SickErrorException )
 Sets the Sick LD signal LED's and switching outputs.
void SetSickTempScanAreas (const double *active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors) throw ( SickTimeoutException, SickIOException, SickConfigException )
 Set the temporary scan areas for the Sick LD.
void SetSickTimeAbsolute (const uint16_t absolute_clock_time, uint16_t &new_sick_clock_time) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException )
 Set the absolute time of the Sick LD unit.
void SetSickTimeRelative (const int16_t time_delta, uint16_t &new_sick_clock_time) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException )
 Set the relative time of the Sick LD unit.
 SickLD (const std::string sick_ip_address=DEFAULT_SICK_IP_ADDRESS, const uint16_t sick_tcp_port=DEFAULT_SICK_TCP_PORT)
 A standard constructor.
void Uninitialize () throw ( SickIOException, SickTimeoutException, SickErrorException, SickThreadException )
 Tear down the connection between the host and the Sick LD.
 ~SickLD ()

Static Public Attributes

static const uint8_t SICK_CONF_KEY_CAN = 0x02
 Key for configuring CAN.
static const uint8_t SICK_CONF_KEY_ETHERNET = 0x05
 Key for configuring Ethernet.
static const uint8_t SICK_CONF_KEY_GLOBAL = 0x10
 Key for global configuration.
static const uint8_t SICK_CONF_KEY_RS232_RS422 = 0x01
 Key for configuring RS-232/RS-422.
static const uint8_t SICK_CONF_SECTOR_NO_MEASUREMENT = 0x01
 Sector has no measurements.
static const uint8_t SICK_CONF_SECTOR_NORMAL_MEASUREMENT = 0x03
 Sector is returning measurements.
static const uint8_t SICK_CONF_SECTOR_NOT_INITIALIZED = 0x00
 Sector is uninitialized.
static const uint8_t SICK_CONF_SECTOR_REFERENCE_MEASUREMENT = 0x04
 Sector can be used as reference measurement.
static const uint8_t SICK_CONF_SECTOR_RESERVED = 0x02
 Sector is reserved by Sick LD.
static const uint8_t SICK_CONF_SERV_CODE = 0x02
 Configuration service code.
static const uint8_t SICK_CONF_SERV_GET_CONFIGURATION = 0x02
 Read the Sick LD configuration information.
static const uint8_t SICK_CONF_SERV_GET_FUNCTION = 0x0B
 Returns the configuration of the given sector.
static const uint8_t SICK_CONF_SERV_GET_SYNC_CLOCK = 0x05
 Read the internal time of the LD-OEM/LD-LRS.
static const uint8_t SICK_CONF_SERV_SET_CONFIGURATION = 0x01
 Set the Sick LD configuration.
static const uint8_t SICK_CONF_SERV_SET_FILTER = 0x09
 Set the filter configuration.
static const uint8_t SICK_CONF_SERV_SET_FILTER_NEARFIELD = 0x01
 Code for identifying filter type: nearfield suppression.
static const uint8_t SICK_CONF_SERV_SET_FILTER_NEARFIELD_OFF = 0x00
 Used to set nearfield suppression off.
static const uint8_t SICK_CONF_SERV_SET_FILTER_NEARFIELD_ON = 0x01
 Used to set nearfield suppression on.
static const uint8_t SICK_CONF_SERV_SET_FUNCTION = 0x0A
 Assigns a measurement function to an angle range.
static const uint8_t SICK_CONF_SERV_SET_TIME_ABSOLUTE = 0x03
 Set the internal clock to a timestamp value.
static const uint8_t SICK_CONF_SERV_SET_TIME_RELATIVE = 0x04
 Correct the internal clock by some value.
static const double SICK_DEGREES_PER_MOTOR_STEP = 0.0625
 Each odometer tick is equivalent to rotating the scan head this many degrees.
static const uint8_t SICK_FILE_SERV_CODE = 0x07
 File service code.
static const uint8_t SICK_FILE_SERV_DELETE = 0x04
 Deletes a file from the flash.
static const uint8_t SICK_FILE_SERV_DIR = 0x01
 List the stored files in flash memory.
static const uint8_t SICK_FILE_SERV_LOAD = 0x03
 Recalls a file from the flash.
static const uint8_t SICK_FILE_SERV_SAVE = 0x02
 Saves the data into flash memory.
static const uint16_t SICK_MAX_MEAN_PULSE_FREQUENCY = 10800
 Max mean pulse frequence of the current device configuration (in Hz) (see page 22 of the operator's manual)
static const uint16_t SICK_MAX_MOTOR_SPEED = 20
 Maximum motor speed in Hz.
static const uint16_t SICK_MAX_NUM_MEASUREMENTS = 2881
 Maximum number of measurements per sector.
static const uint16_t SICK_MAX_NUM_MEASURING_SECTORS = 4
 Maximum number of active/measuring scan sectors.
static const uint16_t SICK_MAX_NUM_SECTORS = 8
 Maximum number of scan sectors (NOTE: This value must be even)
static const uint16_t SICK_MAX_PULSE_FREQUENCY = 14400
 Max pulse frequency of the device (in Hz) (see page 22 of the operator's manual)
static const double SICK_MAX_SCAN_ANGULAR_RESOLUTION = 0.125
 Minimum valid separation between laser pulses in active scan ares (deg)
static const uint16_t SICK_MAX_SCAN_AREA = 360
 Maximum area that can be covered in a single scan (deg)
static const uint16_t SICK_MAX_VALID_SENSOR_ID = 254
 The largest value the Sick will accept as a Sensor ID.
static const uint8_t SICK_MEAS_SERV_CANCEL_PROFILE = 0x02
 Stops profile output.
static const uint8_t SICK_MEAS_SERV_CODE = 0x03
 Measurement service code.
static const uint8_t SICK_MEAS_SERV_GET_PROFILE = 0x01
 Requests n profiles of a defined format.
static const uint16_t SICK_MIN_MOTOR_SPEED = 5
 Minimum motor speed in Hz.
static const uint16_t SICK_MIN_VALID_SENSOR_ID = 1
 The lowest value the Sick will accept as a Sensor ID.
static const uint8_t SICK_MONR_SERV_CODE = 0x08
 Monitor service code.
static const uint8_t SICK_MONR_SERV_MONITOR_PROFILE_LOG = 0x02
 Enable/disable profile logging.
static const uint8_t SICK_MONR_SERV_MONITOR_RUN = 0x01
 Enable/disable monitor services.
static const uint8_t SICK_MOTOR_MODE_ERROR = 0x0B
 Motor stops or coder error.
static const uint8_t SICK_MOTOR_MODE_OK = 0x00
 Motor is functioning properly.
static const uint8_t SICK_MOTOR_MODE_SPIN_TOO_HIGH = 0x09
 Motor spin too low (i.e. rotational velocity too low)
static const uint8_t SICK_MOTOR_MODE_SPIN_TOO_LOW = 0x04
 Motor spin too high (i.e. rotational velocity too fast)
static const uint8_t SICK_MOTOR_MODE_UNKNOWN = 0xFF
 Motor is in an unknown state.
static const uint16_t SICK_NUM_TICKS_PER_MOTOR_REV = 5760
 Odometer ticks per revolution of the Sick LD scan head.
static const uint8_t SICK_ROUT_SERV_CODE = 0x06
 Routing service code.
static const uint8_t SICK_ROUT_SERV_COM_ATTACH = 0x01
 Attach a master (host) communications interface.
static const uint8_t SICK_ROUT_SERV_COM_DATA = 0x05
 Forward data received on specified interface to master interface.
static const uint8_t SICK_ROUT_SERV_COM_DETACH = 0x02
 Detach a master (host) communications interface.
static const uint8_t SICK_ROUT_SERV_COM_INITIALIZE = 0x03
 Initialize the interface (Note: using this may not be necessary for some interfaces, e.g. Ethernet)
static const uint8_t SICK_ROUT_SERV_COM_OUTPUT = 0x04
 Output data to the interface.
static const uint16_t SICK_SCAN_PROFILE_RANGE = 0x39FF
 Request sector scan data w/o any echo data.
static const uint16_t SICK_SCAN_PROFILE_RANGE_AND_ECHO = 0x3DFF
 Request sector scan data w/ echo data.
static const uint8_t SICK_SENSOR_MODE_ERROR = 0x04
 The Sick LD is in error mode.
static const uint8_t SICK_SENSOR_MODE_IDLE = 0x01
 The Sick LD is powered but idle.
static const uint8_t SICK_SENSOR_MODE_MEASURE = 0x03
 The Sick LD prism is rotating, and the laser is on.
static const uint8_t SICK_SENSOR_MODE_ROTATE = 0x02
 The Sick LD prism is rotating, but laser is off.
static const uint8_t SICK_SENSOR_MODE_UNKNOWN = 0xFF
 The Sick LD is in an unknown state.
static const uint8_t SICK_SIGNAL_LED_GREEN = 0x04
 Mask for green LED.
static const uint8_t SICK_SIGNAL_LED_RED = 0x08
 Mask for red LED.
static const uint8_t SICK_SIGNAL_LED_YELLOW_A = 0x01
 Mask for first yellow LED.
static const uint8_t SICK_SIGNAL_LED_YELLOW_B = 0x02
 Mask for second yellow LED.
static const uint8_t SICK_SIGNAL_SWITCH_0 = 0x10
 Mask for signal switch 0.
static const uint8_t SICK_SIGNAL_SWITCH_1 = 0x20
 Mask for signal switch 1.
static const uint8_t SICK_SIGNAL_SWITCH_2 = 0x40
 Mask for signal switch 2.
static const uint8_t SICK_SIGNAL_SWITCH_3 = 0x80
 Mask for signal switch 3.
static const uint8_t SICK_STAT_SERV_CODE = 0x01
 Status service code.
static const uint8_t SICK_STAT_SERV_GET_ID = 0x01
 Request the Sick LD ID.
static const uint8_t SICK_STAT_SERV_GET_ID_APP_NAME = 0x21
 Request the application name.
static const uint8_t SICK_STAT_SERV_GET_ID_APP_PART_NUM = 0x20
 Request the application part number.
static const uint8_t SICK_STAT_SERV_GET_ID_APP_VERSION = 0x22
 Request the application version.
static const uint8_t SICK_STAT_SERV_GET_ID_FIRMWARE_NAME = 0x11
 Request the firmware's name.
static const uint8_t SICK_STAT_SERV_GET_ID_FIRMWARE_PART_NUM = 0x10
 Requess the firmware's part number.
static const uint8_t SICK_STAT_SERV_GET_ID_FIRMWARE_VERSION = 0x12
 Request the firmware's version.
static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_EDM_SERIAL_NUM = 0x04
 Request the edm??? serial number.
static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_NAME = 0x01
 Request the sensor's name.
static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_PART_NUM = 0x00
 Request the sensor's part number.
static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_SERIAL_NUM = 0x03
 Request the sensor's serial number.
static const uint8_t SICK_STAT_SERV_GET_ID_SENSOR_VERSION = 0x02
 Request the sensor's version.
static const uint8_t SICK_STAT_SERV_GET_SIGNAL = 0x04
 Reads the value of the switch and LED port.
static const uint8_t SICK_STAT_SERV_GET_STATUS = 0x02
 Request status information.
static const uint8_t SICK_STAT_SERV_LD_REGISTER_APPLICATION = 0x06
 Registers the ID data for the application firmware.
static const uint8_t SICK_STAT_SERV_SET_SIGNAL = 0x05
 Sets the switches and LEDs.
static const uint8_t SICK_WORK_SERV_CODE = 0x04
 Working service code.
static const uint8_t SICK_WORK_SERV_RESET = 0x01
 Sick LD enters a reset sequence.
static const uint8_t SICK_WORK_SERV_RESET_HALT_APP = 0x02
 Sick LD does a minimal reset (Application is halted and device enters IDLE state)
static const uint8_t SICK_WORK_SERV_RESET_INIT_CPU = 0x00
 Sick LD does a complete reset (Reinitializes the CPU)
static const uint8_t SICK_WORK_SERV_RESET_KEEP_CPU = 0x01
 Sick LD does a partial reset (CPU is not reinitialized)
static const uint8_t SICK_WORK_SERV_TRANS_IDLE = 0x02
 Sick LD enters IDLE mode (motor stops and laser is turned off)
static const uint8_t SICK_WORK_SERV_TRANS_MEASURE = 0x04
 Sick LD enters MEASURE mode (laser starts with next revolution)
static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_MAX_PULSE = 0x01
 Sick LD reports config yields a max laser pulse frequency that is too high.
static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_MEAN_PULSE = 0x02
 Sick LD reports config yields a max mean pulse frequency that is too high.
static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_SECT_BORDER = 0x03
 Sick LD reports sector borders are not configured correctly.
static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_ERR_SECT_BORDER_MULT = 0x04
 Sick LD reports sector borders are not a multiple of the step angle.
static const uint8_t SICK_WORK_SERV_TRANS_MEASURE_RET_OK = 0x00
 Sick LD is ready to stream/obtain scan profiles.
static const uint8_t SICK_WORK_SERV_TRANS_ROTATE = 0x03
 Sick LD enters ROTATE mode (motor starts and rotates with a specified speed in Hz, laser is off)

Private Member Functions

uint16_t _angleToTicks (const double angle) const
 Converts encoder ticks to equivalent angle representation.
void _cancelSickScanProfiles () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Kills the current data stream.
double _computeMaxPulseFrequency (const double total_scan_area, const double curr_motor_speed, const double curr_angular_resolution) const
 Compute the mean pulse frequency (see page 22 of the operator's manual)
double _computeMeanPulseFrequency (const double active_scan_area, const double curr_motor_speed, const double curr_angular_resolution) const
 Compute the mean pulse frequency (see page 22 of the operator's manual)
double _computeScanArea (const double sick_step_angle, const double *const sector_start_angles, const double *const sector_stop_angles, const unsigned int num_sectors) const
 Computes the active scan area for the Sick given the current sector configuration.
void _flushTCPRecvBuffer () throw ( SickIOException, SickThreadException )
 Flushes TCP receive buffer contents.
void _generateSickSectorConfig (const double *const active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors, const double sick_step_angle, unsigned int *const sector_functions, double *const sector_stop_angles, unsigned int &num_sectors) const
void _getApplicationSoftwareName () throw ( SickTimeoutException, SickIOException )
 Get application software name.
void _getApplicationSoftwarePartNumber () throw ( SickTimeoutException, SickIOException )
 Get application software part number.
void _getApplicationSoftwareVersion () throw ( SickTimeoutException, SickIOException )
 Get application software part number.
void _getFirmwareName () throw ( SickTimeoutException, SickIOException )
 Get firmware name.
void _getFirmwarePartNumber () throw ( SickTimeoutException, SickIOException )
 Get firmware part number.
void _getFirmwareVersion () throw ( SickTimeoutException, SickIOException )
 Get firmware version number.
void _getIdentificationString (const uint8_t id_request_code, std::string &id_return_string) throw ( SickTimeoutException, SickIOException )
 Query the Sick LD for a particular ID string.
void _getSensorEDMSerialNumber () throw ( SickTimeoutException, SickIOException )
 Get sensor EDM serial number.
void _getSensorName () throw ( SickTimeoutException, SickIOException )
 Get the Sick LD's assigned sensor name.
void _getSensorPartNumber () throw ( SickTimeoutException, SickIOException )
 Get the Sick LD's part number.
void _getSensorSerialNumber () throw ( SickTimeoutException, SickIOException )
 Get the Sick LD's serial number.
void _getSensorVersion () throw ( SickTimeoutException, SickIOException )
 Get the Sick LD's sensor version.
void _getSickEthernetConfig () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Get the Sick LD's Ethernet configuration.
void _getSickGlobalConfig () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Get the global configuration of the Sick LD.
void _getSickIdentity () throw ( SickTimeoutException, SickIOException )
 Get the parameters that define the Sick LD's identity.
void _getSickScanProfiles (const uint16_t profile_format, const uint16_t num_profiles=DEFAULT_SICK_NUM_SCAN_PROFILES) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException )
 Request n scan profiles from the Sick LD unit.
void _getSickSectorConfig () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Query the Sick for its current sector configuration.
void _getSickSectorFunction (const uint8_t sector_num, uint8_t &sector_function, double &sector_stop_angle) throw ( SickErrorException, SickTimeoutException, SickIOException )
 Acquires the function of the given sector.
void _getSickStatus () throw ( SickTimeoutException, SickIOException )
 Get the status of the Sick LD.
void _parseScanProfile (uint8_t *const src_buffer, sick_ld_scan_profile_t &profile_data) const
 Parses a well-formed sequence of bytes into a corresponding scan profile.
void _printInitFooter () const
 Prints the initialization footer.
void _printSectorProfileData (const sick_ld_sector_data_t &sector_data) const
 Print data corresponding to the referenced sector data structure.
void _printSickScanProfile (const sick_ld_scan_profile_t profile_data, const bool print_sector_data=true) const
 Prints data fields of the given scan profile.
void _sendMessageAndGetReply (const SickLDMessage &send_message, SickLDMessage &recv_message, const unsigned int timeout_value=DEFAULT_SICK_MESSAGE_TIMEOUT) throw ( SickIOException, SickTimeoutException )
 Send a message to the Sick LD and get its reply.
void _setSickFilter (const uint8_t suppress_code) throw ( SickErrorException, SickTimeoutException, SickIOException )
 Enables/disables nearfield suppression on the Sick LD.
void _setSickGlobalConfig (const uint8_t sick_sensor_id, const uint8_t sick_motor_speed, const double sick_angle_step) throw ( SickErrorException, SickTimeoutException, SickIOException )
 Sets the Sick LD's global parameters (sensor id, motor speed, and angular step) in flash.
void _setSickGlobalParamsAndScanAreas (const unsigned int sick_motor_speed, const double sick_step_angle, const double *const active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors) throw ( SickTimeoutException, SickIOException, SickConfigException, SickErrorException )
 Attempts to set the "permanent" (by writing flash) operating values for the device.
void _setSickSectorConfig (const unsigned int *const sector_functions, const double *const sector_stop_angles, const unsigned int num_sectors, const bool write_to_flash=false) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException )
 Sets the sector configuration for the device.
void _setSickSectorFunction (const uint8_t sector_number, const uint8_t sector_function, const double sector_angle_stop, const bool write_to_flash=false) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException )
 Sets the function for a particular scan sector.
void _setSickSensorMode (const uint8_t new_sick_sensor_mode) throw ( SickErrorException, SickTimeoutException, SickIOException )
 Sets the Sick LD to the requested sensor mode.
void _setSickSensorModeToIdle () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Sets the Sick LD sensor mode to IDLE.
void _setSickSensorModeToMeasure () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Sets the Sick LD sensor mode to ROTATE.
void _setSickSensorModeToRotate () throw ( SickErrorException, SickTimeoutException, SickIOException )
 Sets the Sick LD sensor mode to ROTATE.
void _setSickSignals (const uint8_t sick_signal_flags=DEFAULT_SICK_SIGNAL_SET) throw ( SickIOException, SickTimeoutException, SickErrorException )
 Sets the Sick LEDs and switching outputs.
void _setSickTemporaryScanAreas (const double *const active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors) throw ( SickTimeoutException, SickIOException, SickConfigException )
 Attempts to set the "temporary" (until a device reset) scan area config for the device.
void _setupConnection () throw ( SickIOException, SickTimeoutException )
 Establish a TCP connection to the unit.
std::string _sickMotorModeToString (const uint8_t sick_motor_mode) const
 Converts the Sick LD numerical motor mode to a representative string.
std::string _sickProfileFormatToString (const uint16_t profile_format) const
 Converts the Sick LD numerical motor mode to a representative string.
std::string _sickResetLevelToString (const uint16_t reset_level) const
 Converts the Sick LD numerical reset level to a representative string.
std::string _sickSectorFunctionToString (const uint16_t sick_sector_function) const
 Converts the Sick LD numerical sector config to a representative string.
std::string _sickSensorModeToString (const uint8_t sick_sensor_mode) const
 Converts the Sick LD numerical sensor mode to a representative string.
uint8_t _sickSensorModeToWorkServiceSubcode (const uint8_t sick_sensor_mode) const
 Map Sick LD sensor modes to their equivalent service subcode representations.
std::string _sickTransMeasureReturnToString (const uint8_t return_value) const
 Converts return value from TRANS_MEASURE to a representative string.
void _sortScanAreas (double *const sector_start_angles, double *const sector_stop_angles, const unsigned int num_sectors) const
 Sort the scan areas based on the given angles to place them in device "scan" order.
bool _supportedScanProfileFormat (const uint16_t profile_format) const
 Check that the given profile format is supported by the current driver version.
void _syncDriverWithSick () throw ( SickIOException, SickTimeoutException, SickErrorException )
 Synchronizes buffer driver parameters with those of the Sick LD.
void _teardownConnection () throw ( SickIOException )
 Teardown TCP connection to Sick LD.
double _ticksToAngle (const uint16_t ticks) const
 Converts encoder ticks to equivalent angle representation.
bool _validActiveSectors (const double *const sector_start_angles, const double *const sector_stop_angles, const unsigned int num_active_sectors) const
 Determines wheter a given set of sector bounds are valid.
bool _validPulseFrequency (const unsigned int sick_motor_speed, const double sick_step_angle) const
 Checks whether the given configuration yields a valid mean and max pulse frequency (uses current sector config)
bool _validPulseFrequency (const unsigned int sick_motor_speed, const double sick_step_angle, const double *const active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors) const
 Checks whether the given configuration yields a valid mean and max pulse frequency (uses given sector config)
bool _validSickMotorSpeed (const unsigned int sick_motor_speed) const
 Checks whether the given sick motor speed is valid for the device.
bool _validSickScanResolution (const double sick_step_angle, const double *const active_sector_start_angles, const double *const active_sector_stop_angles, const unsigned int num_active_sectors) const
 Checks whether the given scan resolution is valid.
bool _validSickSensorID (const unsigned int sick_sensor_id) const
 Checks whether the given senor id is valid for the device.

Private Attributes

sick_ld_config_ethernet_t _sick_ethernet_config
sick_ld_config_global_t _sick_global_config
sick_ld_identity_t _sick_identity
struct sockaddr_in _sick_inet_address_info
std::string _sick_ip_address
uint8_t _sick_motor_mode
sick_ld_config_sector_t _sick_sector_config
uint8_t _sick_sensor_mode
bool _sick_streaming_range_and_echo_data
bool _sick_streaming_range_data
uint16_t _sick_tcp_port
unsigned int _socket

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 56 of file SickLD.hh.


Member Typedef Documentation

Adopt c-style convention.

Adopt c-style convention.

Adopt c-style convention.

Adopt c-style convention.

Adopt c-style convention.

Adopt c-style convention.


Constructor & Destructor Documentation

SickToolbox::SickLD::SickLD ( const std::string  sick_ip_address = DEFAULT_SICK_IP_ADDRESS,
const uint16_t  sick_tcp_port = DEFAULT_SICK_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 51 of file SickLD.cc.

Destructor

A standard destructor

Definition at line 86 of file SickLD.cc.


Member Function Documentation

uint16_t SickToolbox::SickLD::_angleToTicks ( const double  angle) const [private]

Converts encoder ticks to equivalent angle representation.

Converts angle to an equivalent representation in odometer ticks

Parameters:
ticksThe tick value to be converted
Returns:
The corresponding ticks value

NOTE: This function assumes that the angle value it receives is a multiple of 1/16 degree (which is the resolution of the encoder)

Definition at line 4288 of file SickLD.cc.

Kills the current data stream.

Cancels the active data stream

Definition at line 2687 of file SickLD.cc.

double SickToolbox::SickLD::_computeMaxPulseFrequency ( const double  total_scan_area,
const double  curr_motor_speed,
const double  curr_angular_resolution 
) const [private]

Compute the mean pulse frequency (see page 22 of the operator's manual)

Computes the total pulse frequency for the given config

Parameters:
active_scan_areaThe total scan area that can be covered by the Sick
curr_motor_speedThe current motor speed (in Hz)
curr_angular_resolutionThe current angular resolution of the Sick (in deg)
Returns:
The maximum pulse frequency for the given configuration parameters

Definition at line 4312 of file SickLD.cc.

double SickToolbox::SickLD::_computeMeanPulseFrequency ( const double  active_scan_area,
const double  curr_motor_speed,
const double  curr_angular_resolution 
) const [private]

Compute the mean pulse frequency (see page 22 of the operator's manual)

Computes the mean pulse frequency for the given config

Parameters:
active_scan_areaThe total area where the Sick is actively scanning (in deg) (i.e. total area where the laser isn't blanked)
curr_motor_speedThe current motor speed (in Hz)
curr_angular_resolutionThe current angular resolution of the Sick (in deg)
Returns:
The mean pulse frequency for the given configuration parameters

Definition at line 4299 of file SickLD.cc.

double SickToolbox::SickLD::_computeScanArea ( const double  sick_angle_step,
const double *const  active_sector_start_angles,
const double *const  active_sector_stop_angles,
const unsigned int  num_active_sectors 
) const [private]

Computes the active scan area for the Sick given the current sector configuration.

Returns the scanning area for the device given the current sector configuration

Parameters:
sick_angle_stepThe angular resolution of the Sick LD
active_sector_start_anglesThe start angles for the active scan sectors
active_sector_stop_anglesThe stop angles for the active scan sectors
num_active_sectorsThe number of active sectors
Returns:
The Sick LD scan area corresponding to the given bounds

NOTE: The Sick LD computes scan area by subtracting the end of the previous sector from the end of the current sector. As such, we have to add a single step angle to our computation in order to get the scan area that is used by the Sick LD. Unfortunately, this is how the device does its computation (as opposed to using the angle at which the first scan in the given sector is taken) so this is how we do it.

Definition at line 4444 of file SickLD.cc.

Flushes TCP receive buffer contents.

Flushed the TCP receive buffer

Definition at line 4120 of file SickLD.cc.

void SickToolbox::SickLD::_generateSickSectorConfig ( const double *const  active_sector_start_angles,
const double *const  active_sector_stop_angles,
const unsigned int  num_active_sectors,
const double  sick_angle_step,
unsigned int *const  sector_functions,
double *const  sector_stop_angles,
unsigned int &  num_sectors 
) const [private]

Generates a device-ready sector set given only an active sector spec.

Parameters:
*active_sector_start_anglesStart angles for the active (measuring) sectors
*active_sector_stop_anglesStop angles for the active sectors
num_active_sectorsThe number of active sectors given
sick_angle_stepThe step angle (angular resolution) to be used in generating the config
*sector_functionsAn output buffer to hold the function assigned to each sector
*sector_stop_anglesAn output buffer to hold the stop angles associated w/ the generated sector set
&num_sectorsThe number of sectors in the final device-ready configuration

Definition at line 4187 of file SickLD.cc.

Get application software name.

Query the Sick for the application name

Definition at line 3721 of file SickLD.cc.

Get application software part number.

Query the part number of the application software

Definition at line 3691 of file SickLD.cc.

Get application software part number.

Query the Sick for the application software version

Definition at line 3751 of file SickLD.cc.

Get firmware name.

Query the Sick for the name of its firmware

Definition at line 3631 of file SickLD.cc.

Get firmware part number.

Query the Sick for the part number of its firmware

Definition at line 3601 of file SickLD.cc.

Get firmware version number.

Query the Sick for the version of the firmware

Definition at line 3661 of file SickLD.cc.

void SickToolbox::SickLD::_getIdentificationString ( const uint8_t  id_request_code,
std::string &  id_return_string 
) throw ( SickTimeoutException, SickIOException ) [private]

Query the Sick LD for a particular ID string.

Query the Sick for ID information

Parameters:
id_request_codeThe code indicating what ID string is being requested.
&id_return_stringA reference to hold the string returned from the Sick LD.x

Definition at line 3395 of file SickLD.cc.

Get sensor EDM serial number.

Query the Sick for its EDM unit's serial number

Definition at line 3571 of file SickLD.cc.

Get the Sick LD's assigned sensor name.

Query the Sick for its assigned name

Definition at line 3479 of file SickLD.cc.

Get the Sick LD's part number.

Query the Sick for its sensor part number

Definition at line 3448 of file SickLD.cc.

Get the Sick LD's serial number.

Query the Sick for its serial number

Definition at line 3541 of file SickLD.cc.

Get the Sick LD's sensor version.

Query the Sick for its version number

Definition at line 3510 of file SickLD.cc.

Get the Sick LD's Ethernet configuration.

Query the Sick for its Ethernet configuration parameters

Definition at line 3192 of file SickLD.cc.

Get the global configuration of the Sick LD.

Query the Sick for its global configuration parameters

Definition at line 3088 of file SickLD.cc.

Get the parameters that define the Sick LD's identity.

Stores an image of the Sick LD's identity locally

Definition at line 2885 of file SickLD.cc.

void SickToolbox::SickLD::_getSickScanProfiles ( const uint16_t  profile_format,
const uint16_t  num_profiles = DEFAULT_SICK_NUM_SCAN_PROFILES 
) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) [private]

Request n scan profiles from the Sick LD unit.

Requests n range measurement profiles from the Sick LD

Parameters:
profile_formatThe format for the requested scan profiles
num_profilesThe number of profiles to request from Sick LD. (Default: 0) (NOTE: When num_profiles = 0, the Sick LD continuously streams profile data)

Definition at line 2389 of file SickLD.cc.

Query the Sick for its current sector configuration.

Acquires the configuration (function and stop angle) for each sector

NOTE: Here we only buffer the sector stop angle as this is the only value returned by the GET_FUNCTION command. Using the stop angle does not give enough information to extract the start angle of sectors that aren't "normal measurement".

Definition at line 3318 of file SickLD.cc.

void SickToolbox::SickLD::_getSickSectorFunction ( const uint8_t  sector_num,
uint8_t &  sector_function,
double &  sector_stop_angle 
) throw ( SickErrorException, SickTimeoutException, SickIOException ) [private]

Acquires the function of the given sector.

Acquires the given Sector's function (i.e. current config)

Parameters:
sector_numThe target sector number
&sector_configThe configuration word returned by the Sick LD
&sector_stopThe stop angle of the given sector

Definition at line 2016 of file SickLD.cc.

Get the status of the Sick LD.

Query the Sick for its sensor and motor status

Definition at line 2927 of file SickLD.cc.

void SickToolbox::SickLD::_parseScanProfile ( uint8_t *const  src_buffer,
sick_ld_scan_profile_t profile_data 
) const [private]

Parses a well-formed sequence of bytes into a corresponding scan profile.

Parses a sequence of bytes and populates the profile_data struct w/ the results

Parameters:
*src_bufferThe source data buffer
&profile_dataThe destination data structure

Definition at line 2520 of file SickLD.cc.

void SickToolbox::SickLD::_printInitFooter ( ) const [private]

Prints the initialization footer.

Prints the initialization footer

Definition at line 4750 of file SickLD.cc.

void SickToolbox::SickLD::_printSectorProfileData ( const sick_ld_sector_data_t sector_data) const [private]

Print data corresponding to the referenced sector data structure.

Prints data corresponding to a single scan sector (data obtained using GET_PROFILE)

Parameters:
&sector_dataThe sector configuration to be printed

Definition at line 4557 of file SickLD.cc.

void SickToolbox::SickLD::_printSickScanProfile ( const sick_ld_scan_profile_t  profile_data,
const bool  print_sector_data = true 
) const [private]

Prints data fields of the given scan profile.

Prints the data corresponding to the given scan profile (for debugging purposes)

Parameters:
profile_dataThe scan profile to be printed.
print_sector_dataIndicates whether to print the sector data fields associated with the given profile.

Definition at line 4576 of file SickLD.cc.

void SickToolbox::SickLD::_sendMessageAndGetReply ( const SickLDMessage send_message,
SickLDMessage recv_message,
const unsigned int  timeout_value = DEFAULT_SICK_MESSAGE_TIMEOUT 
) throw ( SickIOException, SickTimeoutException ) [private]

Send a message to the Sick LD and get its reply.

Send a message, get the reply from the Sick LD and check it

Parameters:
&send_messageA reference to the well-formed message object that is to be sent.
&recv_messageThe destination message object for the received reply.
timeout_valueThe maximum time to allow for a response in seconds

NOTE: This method also verifies the correct reply to the given send_message object is received. So, if it fails, it may be due to an unexpected reply.

Definition at line 4083 of file SickLD.cc.

void SickToolbox::SickLD::_setSickFilter ( const uint8_t  suppress_code) throw ( SickErrorException, SickTimeoutException, SickIOException ) [private]

Enables/disables nearfield suppression on the Sick LD.

Turns nearfield suppression on/off

Parameters:
suppress_codeCode indicating whether to enable or diable the nearfield suppression

Definition at line 2790 of file SickLD.cc.

void SickToolbox::SickLD::_setSickGlobalConfig ( const uint8_t  sick_sensor_id,
const uint8_t  sick_motor_speed,
const double  sick_angle_step 
) throw ( SickErrorException, SickTimeoutException, SickIOException ) [private]

Sets the Sick LD's global parameters (sensor id, motor speed, and angular step) in flash.

Sets the Sick LD's global configuration (in flash)

Parameters:
sick_sensor_idThe sensor id to be assigned to the unit.
sick_motor_speedThe speed of the motor in Hz (must be in [5,20])
sick_angular_stepThe difference between two laser pulses in 1/16 degrees (e.g. sick_angular_step = 4 => 0.25 deg step). Also, this value must evenly divide into 5760 and be greater than 1 (see telegram listing page 21).

ALERT: This method writes the parameters to the Sick LD's flash, so there is no need to use it except when configuring the device.

ALERT: This method DOES NOT DO ERROR CHECKING on the given parameter values. It is the responsibility of the caller function to do error checking beforehand.

Definition at line 2988 of file SickLD.cc.

void SickToolbox::SickLD::_setSickGlobalParamsAndScanAreas ( const unsigned int  sick_motor_speed,
const double  sick_angle_step,
const double *const  active_sector_start_angles,
const double *const  active_sector_stop_angles,
const unsigned int  num_active_sectors 
) throw ( SickTimeoutException, SickIOException, SickConfigException, SickErrorException ) [private]

Attempts to set the "permanent" (by writing flash) operating values for the device.

Allows setting the global parameters and scan area definition (in flash)

Parameters:
sick_motor_speedDesired motor speed for the device (hz)
sick_angle_stepDesired scan angular resolution (deg)
active_sector_start_anglesAngles marking the beginning of each desired active sector/area
active_sector_stop_anglesAngles marking the end of each desired active sector/area
num_active_sectorsThe number of active sectors

Definition at line 3786 of file SickLD.cc.

void SickToolbox::SickLD::_setSickSectorConfig ( const unsigned int *const  sector_functions,
const double *const  sector_stop_angles,
const unsigned int  num_sectors,
const bool  write_to_flash = false 
) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) [private]

Sets the sector configuration for the device.

Sets the sick sector configuration

Parameters:
sector_functionsAngles marking the beginning of each desired active sector/area
sector_stop_anglesAngles marking the end of each desired active sector/area
num_sectorsThe total number of sectors in the configuration
set_flash_flagIndicates whether to mark the sectors for writing to flash w/ the next SET_CONFIG (global)

Definition at line 3963 of file SickLD.cc.

void SickToolbox::SickLD::_setSickSectorFunction ( const uint8_t  sector_number,
const uint8_t  sector_function,
const double  sector_stop_angle,
const bool  write_to_flash = false 
) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException ) [private]

Sets the function for a particular scan sector.

Set the function for a particular scan secto

Parameters:
sector_numberThe number of the sector (should be in [0,7])
sector_functionThe function of the sector (e.g. no measurement, reserved, normal measurement, ...)
sector_stop_angleThe last angle of the sector (in odometer ticks)
write_to_flashIndicates whether the sector configuration should be written to flash

Definition at line 1890 of file SickLD.cc.

void SickToolbox::SickLD::_setSickSensorMode ( const uint8_t  new_sick_sensor_mode) throw ( SickErrorException, SickTimeoutException, SickIOException ) [private]

Sets the Sick LD to the requested sensor mode.

Sets the Sick LD's sensor mode to IDLE (laser off, motor off)

Parameters:
new_sick_sensor_modeThe desired sensor mode

Definition at line 2250 of file SickLD.cc.

Sets the Sick LD sensor mode to IDLE.

Sets the Sick LD to IDLE mode

Definition at line 2120 of file SickLD.cc.

Sets the Sick LD sensor mode to ROTATE.

Sets the Sick LD to MEASURE mode

Definition at line 2206 of file SickLD.cc.

Sets the Sick LD sensor mode to ROTATE.

Sets the Sick LD to ROTATE mode

Definition at line 2163 of file SickLD.cc.

Sets the Sick LEDs and switching outputs.

Sets the signals for the device

Parameters:
sick_signal_flagsFlags indicating which LEDs and SWITCHES to activate

NOTE: This method does not preserve the previous state of the Sick's signals. In other words, only the signals flagged in sick_signal_flags will be set - all others will be off!

Definition at line 4023 of file SickLD.cc.

void SickToolbox::SickLD::_setSickTemporaryScanAreas ( const double *const  active_sector_start_angles,
const double *const  active_sector_stop_angles,
const unsigned int  num_active_sectors 
) throw ( SickTimeoutException, SickIOException, SickConfigException ) [private]

Attempts to set the "temporary" (until a device reset) scan area config for the device.

Allows setting a temporary (until a device reset) sector configuration on the device

Parameters:
active_sector_start_anglesAngles marking the beginning of each desired active sector/area
active_sector_stop_anglesAngles marking the end of each desired active sector/area
num_active_sectorsThe number of active sectors

Definition at line 3885 of file SickLD.cc.

Establish a TCP connection to the unit.

Setup the connection parameters and establish TCP connection!

Implements SickToolbox::SickLIDAR< SickLDBufferMonitor, SickLDMessage >.

Definition at line 1732 of file SickLD.cc.

std::string SickToolbox::SickLD::_sickMotorModeToString ( const uint8_t  sick_motor_mode) const [private]

Converts the Sick LD numerical motor mode to a representative string.

Converts _sick_motor_mode to a representative string

Parameters:
sick_motor_modeThe sick motor mode code to be converted
Returns:
The corresponding string

Definition at line 4643 of file SickLD.cc.

std::string SickToolbox::SickLD::_sickProfileFormatToString ( const uint16_t  profile_format) const [private]

Converts the Sick LD numerical motor mode to a representative string.

Converts a given scan profile format to a string for friendlier output

Parameters:
profile_formatThe profile format to be converted
Returns:
The corresponding string

Definition at line 4734 of file SickLD.cc.

std::string SickToolbox::SickLD::_sickResetLevelToString ( const uint16_t  reset_level) const [private]

Converts the Sick LD numerical reset level to a representative string.

Converts the specified reset level to a representative string

Parameters:
Thenumeric reset level code
Returns:
The corresponding string

Definition at line 4690 of file SickLD.cc.

std::string SickToolbox::SickLD::_sickSectorFunctionToString ( const uint16_t  sick_sector_function) const [private]

Converts the Sick LD numerical sector config to a representative string.

Converts Sick LD sector configuration word to a representative string

Parameters:
sick_sector_functionThe numeric sector function to be converted
Returns:
The corresponding string

Definition at line 4710 of file SickLD.cc.

std::string SickToolbox::SickLD::_sickSensorModeToString ( const uint8_t  sick_sensor_mode) const [private]

Converts the Sick LD numerical sensor mode to a representative string.

Converts _sick_sensor_mode to a representative string

Parameters:
sick_sensor_modeThe sensor mode to be converted
Returns:
The corresponding sensor_mode string

Definition at line 4620 of file SickLD.cc.

uint8_t SickToolbox::SickLD::_sickSensorModeToWorkServiceSubcode ( const uint8_t  sick_sensor_mode) const [private]

Map Sick LD sensor modes to their equivalent service subcode representations.

Returns the corresponding work service subcode required to transition the Sick LD to the given sensor mode.

Parameters:
sick_sensor_modeThe sensor mode to be converted
Returns:
The corresponding work service subcode

Definition at line 4600 of file SickLD.cc.

std::string SickToolbox::SickLD::_sickTransMeasureReturnToString ( const uint8_t  return_value) const [private]

Converts return value from TRANS_MEASURE to a representative string.

Converts the specified trans measurement mode return value to a string

Parameters:
return_valueThe TRANS_MEASURE numeric return code
Returns:
The corresponding string

Definition at line 4666 of file SickLD.cc.

void SickToolbox::SickLD::_sortScanAreas ( double *const  sector_start_angles,
double *const  sector_stop_angles,
const unsigned int  num_sectors 
) const [private]

Sort the scan areas based on the given angles to place them in device "scan" order.

Reorders given sector angle sets

Parameters:
sector_start_anglesArray of angles (deg) defining the starting position of each active sector
sector_stop_anglesArray of angles (deg) defining the stopping position of each active sector
num_active_sectorsNumber of active sectors

Definition at line 4472 of file SickLD.cc.

bool SickToolbox::SickLD::_supportedScanProfileFormat ( const uint16_t  profile_format) const [private]

Check that the given profile format is supported by the current driver version.

Indicates whether the supplied profile format is currently supported by the driver

Parameters:
profile_formatThe requested profile format.
Returns:
True if the given scan profile is supported by the driver

Definition at line 4540 of file SickLD.cc.

Synchronizes buffer driver parameters with those of the Sick LD.

Synchronizes the driver state with the Sick LD (used for initialization)

Todo:
Add support in this method for acquiring RS-232/RS-422, and CAN configurations

Definition at line 1841 of file SickLD.cc.

void SickToolbox::SickLD::_teardownConnection ( ) throw ( SickIOException ) [private, virtual]

Teardown TCP connection to Sick LD.

Teardown the connection to the Sick LD

Implements SickToolbox::SickLIDAR< SickLDBufferMonitor, SickLDMessage >.

Definition at line 4168 of file SickLD.cc.

double SickToolbox::SickLD::_ticksToAngle ( const uint16_t  ticks) const [private]

Converts encoder ticks to equivalent angle representation.

Converts odometry ticks to an equivalent angle

Parameters:
ticksThe tick value to be converted
Returns:
The corresponding angle value

Definition at line 4275 of file SickLD.cc.

bool SickToolbox::SickLD::_validActiveSectors ( const double *const  sector_start_angles,
const double *const  sector_stop_angles,
const unsigned int  num_sectors 
) const [private]

Determines wheter a given set of sector bounds are valid.

Checks the given sector arguments for overlapping regions yielding an invalid configuration

Parameters:
sector_start_anglesArray of angles (deg) defining the starting position of each active sector
sector_stop_anglesArray of angles (deg) defining the stopping position of each active sector
num_active_sectorsNumber of active sectors

Definition at line 4496 of file SickLD.cc.

bool SickToolbox::SickLD::_validPulseFrequency ( const unsigned int  sick_motor_speed,
const double  sick_angle_step 
) const [private]

Checks whether the given configuration yields a valid mean and max pulse frequency (uses current sector config)

Indicates whether the given configuration yields a valid max and mean pulse frequency

Parameters:
sick_motor_speedDesired sick motor speed (Hz)
sick_angle_stepDesired scan angular resolution (deg)

Definition at line 4383 of file SickLD.cc.

bool SickToolbox::SickLD::_validPulseFrequency ( const unsigned int  sick_motor_speed,
const double  sick_angle_step,
const double *const  active_sector_start_angles,
const double *const  active_sector_stop_angles,
const unsigned int  num_active_sectors 
) const [private]

Checks whether the given configuration yields a valid mean and max pulse frequency (uses given sector config)

Indicates whether the given configuration yields a valid max and mean pulse frequency

Parameters:
sick_motor_speedDesired sick motor speed (Hz)
sick_angle_stepDesired scan angular resolution (deg)
active_sector_start_anglesAngles marking the beginning of each desired active sector/area
active_sector_stop_anglesAngles marking the end of each desired active sector/area
num_active_sectorsThe number of active sectors/scan areas are given

Definition at line 4403 of file SickLD.cc.

bool SickToolbox::SickLD::_validSickMotorSpeed ( const unsigned int  sick_motor_speed) const [private]

Checks whether the given sick motor speed is valid for the device.

Indicates whether a given motor speed is valid for the device

Parameters:
sick_motor_speedThe sick motor speed (Hz)

Definition at line 4337 of file SickLD.cc.

bool SickToolbox::SickLD::_validSickScanResolution ( const double  sick_angle_step,
const double *const  sector_start_angles,
const double *const  sector_stop_angles,
const unsigned int  num_sectors 
) const [private]

Checks whether the given scan resolution is valid.

Indicates whether a given motor speed is valid for the device

Parameters:
sick_scan_resolutionScan resolution of the device
sector_start_anglesAn array of the sector start angles
sector_stop_anglesAn array of the sector stop angles

Definition at line 4354 of file SickLD.cc.

bool SickToolbox::SickLD::_validSickSensorID ( const unsigned int  sick_sensor_id) const [private]

Checks whether the given senor id is valid for the device.

Indicates whether a given sensor ID is valid for the device

Parameters:
sick_sensor_idSick sensor ID

Definition at line 4322 of file SickLD.cc.

Disables nearfield suppressive filtering.

Disables nearfield suppressive filtering (in flash)

NOTE: This method writes this option to the Sick LD's flash, so there is no need to use it except when configuring the device.

Definition at line 668 of file SickLD.cc.

Enables nearfield suppressive filtering.

Enables nearfield suppressive filtering (in flash)

NOTE: This method writes this option to the Sick LD's flash, so there is no need to use it except when configuring the device.

Definition at line 619 of file SickLD.cc.

Acquire the Sick LD's application software name.

Acquire the Sick LD's application software name

Returns:
The Sick LD application software name

Definition at line 1484 of file SickLD.cc.

Acquire the Sick LD's application software part number.

Acquire the Sick LD's application software part number

Returns:
The Sick LD application software part number

Definition at line 1476 of file SickLD.cc.

Acquire the Sick LD's application software version number.

Acquire the Sick LD's application software version number

Returns:
The Sick LD application software version number

Definition at line 1492 of file SickLD.cc.

Acquire the Sick LD's EDM serial number.

Acquire the Sick LD's EDM serial number

Returns:
The Sick LD EDM serial number

Definition at line 1444 of file SickLD.cc.

Acquire the Sick LD's global config as a printable string.

Acquire the Sick LD's Ethernet config as a printable string

Returns:
The Sick LD Ethernet config as a well-formatted string

Definition at line 1561 of file SickLD.cc.

Acquire the Sick LD's firmware number.

Acquire the Sick LD's firmware number

Returns:
The Sick LD firmware name

Definition at line 1460 of file SickLD.cc.

Acquire the Sick LD's firmware part number.

Acquire the Sick LD's firmware part number

Returns:
The Sick LD firmware part number

Definition at line 1452 of file SickLD.cc.

Acquire the Sick LD's firmware version.

Acquire the Sick LD's firmware version

Returns:
The Sick LD firmware version

Definition at line 1468 of file SickLD.cc.

Acquire the IP address of the Sick gateway.

Acquire the IP address of the Sick gateway

Returns:
The Sick LD gateway IP address

Definition at line 1393 of file SickLD.cc.

Acquire the Sick LD's global config as a printable string.

Acquire the Sick LD's global config as a printable string

Returns:
The Sick LD global config as a well-formatted string

Definition at line 1543 of file SickLD.cc.

Acquire the Sick LD's identity as a printable string.

Acquire the Sick LD's identity as a printable string

Returns:
The Sick LD identity as a well-formatted string

Definition at line 1517 of file SickLD.cc.

Acquire the current IP address of the Sick.

Acquire the current IP address of the Sick

Returns:
The Sick LD IP (Inet4) address

Definition at line 1355 of file SickLD.cc.

void SickToolbox::SickLD::GetSickMeasurements ( double *const  range_measurements,
unsigned int *const  echo_measurements = NULL,
unsigned int *const  num_measurements = NULL,
unsigned int *const  sector_ids = NULL,
unsigned int *const  sector_data_offsets = NULL,
double *const  sector_step_angles = NULL,
double *const  sector_start_angles = NULL,
double *const  sector_stop_angles = NULL,
unsigned int *const  sector_start_timestamps = NULL,
unsigned int *const  sector_stop_timestamps = NULL 
) throw ( SickErrorException, SickIOException, SickTimeoutException, SickConfigException )

Acquires measurements and corresponding sector data from the Sick LD.

Acquires measurements and related data for all active sectors

Parameters:
*range_measurementsA single array to hold ALL RANGE MEASUREMENTS from the current scan for all active sectors. Range values from each sector are stored block sequentially in this buffer. The respective index into the array marking the first data value returned by active sector i can be found by getting: range_measurement[sector_data_offsets[i]].
*echo_measurementsA single array to hold ALL ECHO MEASUREMENTS from the current scan for all active sectors. It is indexed the same as range_measurements. This argument is optional and if it is not provided the driver will request a RANGE ONLY data stream as opposed to a RANGE+ECHO thereby reducing consumed bandwidth (Default: NULL).
*num_measurementsAn array where the ith element denotes the number of range/echo measurements obtained from active sector i (Default: NULL).
*sector_idsAn array where the ith element corresponds to the actual sector number/id of the ith active sector. (Default: NULL)
*sector_data_offsetsThe index offsets mapping the ith active sector to the position in range_measurements where its first measured value can be found (Default: NULL).
*sector_step_anglesAn array where the ith element corresponds to the angle step for the ith active sector. (Default: NULL)
*sector_start_anglesAn array where the ith element corresponds to the starting scan angle of the ith active sector.
*sector_stop_anglesAn array where the ith element corresponds to the stop scan angle of the ith active sector.
*sector_start_timestampsAn array where the ith element denotes the time at which the first scan was taken for the ith active sector.
*sector_stop_timestampsAn array where the ith element denotes the time at which the last scan was taken for the ith active sector.

ALERT: The user is responsible for ensuring that enough space is allocated for the return buffers to avoid overflow. See the example code for an easy way to do this.

Definition at line 740 of file SickLD.cc.

Acquire the Sick LD's current motor speed in Hz.

Acquire the Sick LD's current motor speed in Hz

Returns:
The Sick LD motor speed

Definition at line 1339 of file SickLD.cc.

std::string SickToolbox::SickLD::GetSickName ( ) const

Acquire the Sick LD's name.

Acquire the Sick LD's name

Returns:
The Sick LD sensor name

Definition at line 1420 of file SickLD.cc.

Acquire the number of sectors that are measuring.

Returns the number of active/measuring sectors

Returns:
The number of sectors currently measuring

Definition at line 1323 of file SickLD.cc.

Acquire the Sick LD's part number.

Acquire the Sick LD's part number

Returns:
The Sick LD part number

Definition at line 1412 of file SickLD.cc.

Computes the active area over all measuring sectors.

Acquire the total scan area (in degrees) being scanned by the Sick LD

Returns:
The Sick LD active scan area

Definition at line 1605 of file SickLD.cc.

Acquire the Sick LD's current scan resolution.

Acquire the Sick LD's current scan resolution

Returns:
The Sick LD scan resolution

Definition at line 1347 of file SickLD.cc.

Acquire the Sick LD's sector config as a printable string.

Acquire the Sick LD's sector config as a printable string

Returns:
The Sick LD Sick LD's config as a well-formatted string

Definition at line 1579 of file SickLD.cc.

unsigned int SickToolbox::SickLD::GetSickSensorID ( ) const

Acquire the Sick LD's sensor ID.

Acquire the Sick LD's sensor ID

Returns:
The Sick LD sensor ID

Definition at line 1331 of file SickLD.cc.

Acquire the Sick LD's serial number.

Acquire the Sick LD's serial number

Returns:
The Sick LD serial number

Definition at line 1436 of file SickLD.cc.

void SickToolbox::SickLD::GetSickSignals ( uint8_t &  sick_signal_flags) throw ( SickIOException, SickTimeoutException )

Gets the Sick LD signal LED's and switching outputs.

Query the Sick for its current signal settings

Parameters:
&sick_signal_flagsThe destination buffer to hold the returned flags.

Definition at line 497 of file SickLD.cc.

void SickToolbox::SickLD::GetSickStatus ( unsigned int &  sick_sensor_mode,
unsigned int &  sick_motor_mode 
) throw ( SickIOException, SickTimeoutException )

Acquires the status of the Sick from the device.

Gets the sensor and motor mode of the unit

Parameters:
&sick_sensor_modeThe returned sensor mode of the device
&sick_motor_modeThe returned motor mode of the device

Definition at line 146 of file SickLD.cc.

Acquire the Sick LD's status as a printable string.

Acquire the Sick LD's status as a printable string

Returns:
The Sick LD status as a well-formatted string

Definition at line 1500 of file SickLD.cc.

Acquire the subnet mask for the Sick.

Acquire the subnet mask for the Sick

Returns:
The Sick LD subnet mask

Definition at line 1374 of file SickLD.cc.

Gets the internal clock time of the Sick LD unit.

Gets the internal clock time of the Sick LD unit

Parameters:
&sick_timeThe sick clock time in milliseconds.

Definition at line 557 of file SickLD.cc.

std::string SickToolbox::SickLD::GetSickVersion ( ) const

Acquire the Sick LD's version number.

Acquire the Sick LD's version number

Returns:
The Sick LD version number

Definition at line 1428 of file SickLD.cc.

Initializes the driver and syncs it with Sick LD unit. Uses sector config given in flash.

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

Definition at line 91 of file SickLD.cc.

Print the Sick LD's Ethernet configuration.

Prints the Ethernet configuration parameter values

Definition at line 1645 of file SickLD.cc.

Print the Sick LD's global configuration.

Prints the global configuration parameter values

Definition at line 1638 of file SickLD.cc.

Print the parameters comprising the Sick LD's identity.

Prints the Sick LD's identity information

Definition at line 1631 of file SickLD.cc.

Print the Sick LD's sector configuration.

Prints the Sick Sector configuration

Definition at line 1652 of file SickLD.cc.

Print the status of the Sick LD.

Prints the Sick LD's status information

Definition at line 1624 of file SickLD.cc.

Resets the device according to the given reset level.

Resets the Sick LD using the given reset level

Parameters:
reset_levelThe desired reset level (see page 33 of the telegram listing)

Definition at line 1252 of file SickLD.cc.

void SickToolbox::SickLD::SetSickGlobalParamsAndScanAreas ( const unsigned int  sick_motor_speed,
const double  sick_angle_step,
const double *const  active_sector_start_angles,
const double *const  active_sector_stop_angles,
const unsigned int  num_active_sectors 
) throw ( SickTimeoutException, SickIOException, SickConfigException, SickErrorException )

Attempts to set the scan resolution and active sectors/scan areas for the device (in flash)

Attempts to set the global params and the active scan sectors for the device (in flash)

Parameters:
sick_motor_speedDesired sick motor speed (Hz)
sick_angle_stepDesired scan angular resolution (deg)
active_sector_start_anglesAngles marking the beginning of each desired active sector/area
active_sector_stop_anglesAngles marking the end of each desired active sector/area
num_active_sectorsThe number of active sectors/scan areas are given

Definition at line 1140 of file SickLD.cc.

void SickToolbox::SickLD::SetSickMotorSpeed ( const unsigned int  sick_motor_speed) throw ( SickErrorException, SickTimeoutException, SickIOException )

Attempts to set a new motor speed for the device (in flash)

Parameters:
sick_motor_speedThe desired motor speed (Hz)

Definition at line 1040 of file SickLD.cc.

void SickToolbox::SickLD::SetSickScanAreas ( const double *const  active_sector_start_angles,
const double *const  active_sector_stop_angles,
const unsigned int  num_active_sectors 
) throw ( SickTimeoutException, SickIOException, SickConfigException, SickErrorException )

Attempts to set the active scan areas for the device (in flash)

Attempts to set the active scan sectors for the device (in flash)

Parameters:
active_sector_start_anglesAngles marking the beginning of each desired active sector/area
active_sector_stop_anglesAngles marking the end of each desired active sector/area
num_active_sectorsThe number of active sectors/scan areas are given

Definition at line 1198 of file SickLD.cc.

Attempts to set a new scan resolution for the device (in flash) while retaining the previously defined active scan areas.

Attempts to set a new scan resolution for the device (in flash)

Parameters:
sick_angle_stepThe desired scan resolution (deg)

NOTE: Since the Sick determines the active sector bounds based upon the current scan resolution and sector stop angles, it is possible that when the scan resolution is changed so too are the active sector bounds. As such, we also write the correct sector config to flash as opposed to letting the Sick LD just figure it out itself. Doing so ensures the previous active sector definitions remain intact.

Definition at line 1102 of file SickLD.cc.

void SickToolbox::SickLD::SetSickSensorID ( const unsigned int  sick_sensor_id) throw ( SickErrorException, SickTimeoutException, SickIOException )

Attempts to set a new sensor ID for the device (in flash)

Attempts to set a new senor ID for the device (in flash)

Parameters:
sick_sensor_idThe desired sensor ID

Definition at line 991 of file SickLD.cc.

Sets the Sick LD signal LED's and switching outputs.

Sets the signal LEDs and switches

Parameters:
sick_signal_flagsIndicates the LEDs and switches to set/unset.

NOTE: This method does not preserve the previous state of the Sick's signals. In other words, only the signals flagged in sick_signal_flags will be set - all others will be off!

Definition at line 453 of file SickLD.cc.

void SickToolbox::SickLD::SetSickTempScanAreas ( const double *  active_sector_start_angles,
const double *const  active_sector_stop_angles,
const unsigned int  num_active_sectors 
) throw ( SickTimeoutException, SickIOException, SickConfigException )

Set the temporary scan areas for the Sick LD.

Sets the temporal scan configuration (until power is cycled)

Parameters:
*active_sector_start_anglesAngles marking the beginning of each desired active sector/area
*active_sector_stop_anglesAngles marking the end of each desired active sector/area
num_active_sectorsThe number of active sectors

NOTE: The active scan areas set at this point are only maintained until a device reset occurs. In other words, they are not written to flash.

Definition at line 190 of file SickLD.cc.

void SickToolbox::SickLD::SetSickTimeAbsolute ( const uint16_t  absolute_clock_time,
uint16_t &  new_sick_clock_time 
) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException )

Set the absolute time of the Sick LD unit.

Sets the internal clock of the Sick LD unit

Parameters:
absolute_clock_timeThe absolute clock time in milliseconds
new_sick_clock_timeThe clock time in milliseconds returned from the device

ALERT: If the Sick LD is in MEASUREMENT mode, this method will first set the device to ROTATE mode after killing any active data streams (as per the protocol).

Definition at line 241 of file SickLD.cc.

void SickToolbox::SickLD::SetSickTimeRelative ( const int16_t  delta_time,
uint16_t &  new_sick_clock_time 
) throw ( SickErrorException, SickTimeoutException, SickIOException, SickConfigException )

Set the relative time of the Sick LD unit.

Sets the internal clock of the Sick LD using the relative given time value

Parameters:
delta_timeThe relative clock time in milliseconds.
&new_sick_clock_timeThe new time as reported by the Sick LD.

ALERT: If the Sick LD is in MEASUREMENT mode, this method will first set the device to ROTATE mode after killing any active data streams (as per the protocol).

Definition at line 347 of file SickLD.cc.

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

Uninitializes the Sick LD unit

Definition at line 1659 of file SickLD.cc.


Member Data Documentation

The current Ethernet configuration for the unit

Definition at line 578 of file SickLD.hh.

The current global configuration for the unit

Definition at line 575 of file SickLD.hh.

The identity structure for the Sick

Definition at line 572 of file SickLD.hh.

struct sockaddr_in SickToolbox::SickLD::_sick_inet_address_info [private]

Sick LD socket address structure

Definition at line 557 of file SickLD.hh.

The Sick LD IP address

Definition at line 548 of file SickLD.hh.

The mode of the motor

Definition at line 563 of file SickLD.hh.

The current sector configuration for the unit

Definition at line 581 of file SickLD.hh.

The current sensor mode

Definition at line 560 of file SickLD.hh.

Indicates whether the Sick LD is currently streaming range and echo data

Definition at line 569 of file SickLD.hh.

Indicates whether the Sick LD is currently streaming range data

Definition at line 566 of file SickLD.hh.

The Sick LD TCP port number

Definition at line 551 of file SickLD.hh.

unsigned int SickToolbox::SickLD::_socket [private]

Sick LD socket structure

Definition at line 554 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_KEY_CAN = 0x02 [static]

Key for configuring CAN.

Definition at line 176 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_KEY_ETHERNET = 0x05 [static]

Key for configuring Ethernet.

Definition at line 177 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_KEY_GLOBAL = 0x10 [static]

Key for global configuration.

Definition at line 178 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_KEY_RS232_RS422 = 0x01 [static]

Key for configuring RS-232/RS-422.

Definition at line 175 of file SickLD.hh.

Sector has no measurements.

Definition at line 182 of file SickLD.hh.

Sector is returning measurements.

Definition at line 184 of file SickLD.hh.

Sector is uninitialized.

Definition at line 181 of file SickLD.hh.

Sector can be used as reference measurement.

Definition at line 185 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_SECTOR_RESERVED = 0x02 [static]

Sector is reserved by Sick LD.

Definition at line 183 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_SERV_CODE = 0x02 [static]

Configuration service code.

Definition at line 91 of file SickLD.hh.

Read the Sick LD configuration information.

Definition at line 120 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_SERV_GET_FUNCTION = 0x0B [static]

Returns the configuration of the given sector.

Definition at line 126 of file SickLD.hh.

Read the internal time of the LD-OEM/LD-LRS.

Definition at line 123 of file SickLD.hh.

Set the Sick LD configuration.

Definition at line 119 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_SERV_SET_FILTER = 0x09 [static]

Set the filter configuration.

Definition at line 124 of file SickLD.hh.

Code for identifying filter type: nearfield suppression.

Definition at line 129 of file SickLD.hh.

Used to set nearfield suppression off.

Definition at line 132 of file SickLD.hh.

Used to set nearfield suppression on.

Definition at line 133 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_CONF_SERV_SET_FUNCTION = 0x0A [static]

Assigns a measurement function to an angle range.

Definition at line 125 of file SickLD.hh.

Set the internal clock to a timestamp value.

Definition at line 121 of file SickLD.hh.

Correct the internal clock by some value.

Definition at line 122 of file SickLD.hh.

const double SickToolbox::SickLD::SICK_DEGREES_PER_MOTOR_STEP = 0.0625 [static]

Each odometer tick is equivalent to rotating the scan head this many degrees.

Definition at line 73 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_FILE_SERV_CODE = 0x07 [static]

File service code.

Definition at line 95 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_FILE_SERV_DELETE = 0x04 [static]

Deletes a file from the flash.

Definition at line 168 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_FILE_SERV_DIR = 0x01 [static]

List the stored files in flash memory.

Definition at line 165 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_FILE_SERV_LOAD = 0x03 [static]

Recalls a file from the flash.

Definition at line 167 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_FILE_SERV_SAVE = 0x02 [static]

Saves the data into flash memory.

Definition at line 166 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MAX_MEAN_PULSE_FREQUENCY = 10800 [static]

Max mean pulse frequence of the current device configuration (in Hz) (see page 22 of the operator's manual)

Definition at line 69 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MAX_MOTOR_SPEED = 20 [static]

Maximum motor speed in Hz.

Definition at line 66 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MAX_NUM_MEASUREMENTS = 2881 [static]

Maximum number of measurements per sector.

Definition at line 61 of file SickLD.hh.

Maximum number of active/measuring scan sectors.

Definition at line 63 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MAX_NUM_SECTORS = 8 [static]

Maximum number of scan sectors (NOTE: This value must be even)

Definition at line 62 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MAX_PULSE_FREQUENCY = 14400 [static]

Max pulse frequency of the device (in Hz) (see page 22 of the operator's manual)

Definition at line 70 of file SickLD.hh.

Minimum valid separation between laser pulses in active scan ares (deg)

Definition at line 72 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MAX_SCAN_AREA = 360 [static]

Maximum area that can be covered in a single scan (deg)

Definition at line 64 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MAX_VALID_SENSOR_ID = 254 [static]

The largest value the Sick will accept as a Sensor ID.

Definition at line 68 of file SickLD.hh.

Stops profile output.

Definition at line 137 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_MEAS_SERV_CODE = 0x03 [static]

Measurement service code.

Definition at line 92 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_MEAS_SERV_GET_PROFILE = 0x01 [static]

Requests n profiles of a defined format.

Definition at line 136 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MIN_MOTOR_SPEED = 5 [static]

Minimum motor speed in Hz.

Definition at line 65 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_MIN_VALID_SENSOR_ID = 1 [static]

The lowest value the Sick will accept as a Sensor ID.

Definition at line 67 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_MONR_SERV_CODE = 0x08 [static]

Monitor service code.

Definition at line 96 of file SickLD.hh.

Enable/disable profile logging.

Definition at line 172 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_MONR_SERV_MONITOR_RUN = 0x01 [static]

Enable/disable monitor services.

Definition at line 171 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_MOTOR_MODE_ERROR = 0x0B [static]

Motor stops or coder error.

Definition at line 86 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_MOTOR_MODE_OK = 0x00 [static]

Motor is functioning properly.

Definition at line 83 of file SickLD.hh.

Motor spin too low (i.e. rotational velocity too low)

Definition at line 84 of file SickLD.hh.

Motor spin too high (i.e. rotational velocity too fast)

Definition at line 85 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_MOTOR_MODE_UNKNOWN = 0xFF [static]

Motor is in an unknown state.

Definition at line 87 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_NUM_TICKS_PER_MOTOR_REV = 5760 [static]

Odometer ticks per revolution of the Sick LD scan head.

Definition at line 71 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_ROUT_SERV_CODE = 0x06 [static]

Routing service code.

Definition at line 94 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_ROUT_SERV_COM_ATTACH = 0x01 [static]

Attach a master (host) communications interface.

Definition at line 158 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_ROUT_SERV_COM_DATA = 0x05 [static]

Forward data received on specified interface to master interface.

Definition at line 162 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_ROUT_SERV_COM_DETACH = 0x02 [static]

Detach a master (host) communications interface.

Definition at line 159 of file SickLD.hh.

Initialize the interface (Note: using this may not be necessary for some interfaces, e.g. Ethernet)

Definition at line 160 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_ROUT_SERV_COM_OUTPUT = 0x04 [static]

Output data to the interface.

Definition at line 161 of file SickLD.hh.

const uint16_t SickToolbox::SickLD::SICK_SCAN_PROFILE_RANGE = 0x39FF [static]

Request sector scan data w/o any echo data.

Definition at line 188 of file SickLD.hh.

Request sector scan data w/ echo data.

Definition at line 212 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SENSOR_MODE_ERROR = 0x04 [static]

The Sick LD is in error mode.

Definition at line 79 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SENSOR_MODE_IDLE = 0x01 [static]

The Sick LD is powered but idle.

Definition at line 76 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SENSOR_MODE_MEASURE = 0x03 [static]

The Sick LD prism is rotating, and the laser is on.

Definition at line 78 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SENSOR_MODE_ROTATE = 0x02 [static]

The Sick LD prism is rotating, but laser is off.

Definition at line 77 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SENSOR_MODE_UNKNOWN = 0xFF [static]

The Sick LD is in an unknown state.

Definition at line 80 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SIGNAL_LED_GREEN = 0x04 [static]

Mask for green LED.

Definition at line 244 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SIGNAL_LED_RED = 0x08 [static]

Mask for red LED.

Definition at line 245 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SIGNAL_LED_YELLOW_A = 0x01 [static]

Mask for first yellow LED.

Definition at line 242 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SIGNAL_LED_YELLOW_B = 0x02 [static]

Mask for second yellow LED.

Definition at line 243 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SIGNAL_SWITCH_0 = 0x10 [static]

Mask for signal switch 0.

Definition at line 246 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SIGNAL_SWITCH_1 = 0x20 [static]

Mask for signal switch 1.

Definition at line 247 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SIGNAL_SWITCH_2 = 0x40 [static]

Mask for signal switch 2.

Definition at line 248 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_SIGNAL_SWITCH_3 = 0x80 [static]

Mask for signal switch 3.

Definition at line 249 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_STAT_SERV_CODE = 0x01 [static]

Status service code.

Definition at line 90 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_STAT_SERV_GET_ID = 0x01 [static]

Request the Sick LD ID.

Definition at line 99 of file SickLD.hh.

Request the application name.

Definition at line 115 of file SickLD.hh.

Request the application part number.

Definition at line 114 of file SickLD.hh.

Request the application version.

Definition at line 116 of file SickLD.hh.

Request the firmware's name.

Definition at line 112 of file SickLD.hh.

Requess the firmware's part number.

Definition at line 111 of file SickLD.hh.

Request the firmware's version.

Definition at line 113 of file SickLD.hh.

Request the edm??? serial number.

Definition at line 110 of file SickLD.hh.

Request the sensor's name.

Definition at line 107 of file SickLD.hh.

Request the sensor's part number.

Definition at line 106 of file SickLD.hh.

Request the sensor's serial number.

Definition at line 109 of file SickLD.hh.

Request the sensor's version.

Definition at line 108 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_STAT_SERV_GET_SIGNAL = 0x04 [static]

Reads the value of the switch and LED port.

Definition at line 101 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_STAT_SERV_GET_STATUS = 0x02 [static]

Request status information.

Definition at line 100 of file SickLD.hh.

Registers the ID data for the application firmware.

Definition at line 103 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_STAT_SERV_SET_SIGNAL = 0x05 [static]

Sets the switches and LEDs.

Definition at line 102 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_WORK_SERV_CODE = 0x04 [static]

Working service code.

Definition at line 93 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_WORK_SERV_RESET = 0x01 [static]

Sick LD enters a reset sequence.

Definition at line 140 of file SickLD.hh.

Sick LD does a minimal reset (Application is halted and device enters IDLE state)

Definition at line 148 of file SickLD.hh.

Sick LD does a complete reset (Reinitializes the CPU)

Definition at line 146 of file SickLD.hh.

Sick LD does a partial reset (CPU is not reinitialized)

Definition at line 147 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_WORK_SERV_TRANS_IDLE = 0x02 [static]

Sick LD enters IDLE mode (motor stops and laser is turned off)

Definition at line 141 of file SickLD.hh.

Sick LD enters MEASURE mode (laser starts with next revolution)

Definition at line 143 of file SickLD.hh.

Sick LD reports config yields a max laser pulse frequency that is too high.

Definition at line 152 of file SickLD.hh.

Sick LD reports config yields a max mean pulse frequency that is too high.

Definition at line 153 of file SickLD.hh.

Sick LD reports sector borders are not configured correctly.

Definition at line 154 of file SickLD.hh.

Sick LD reports sector borders are not a multiple of the step angle.

Definition at line 155 of file SickLD.hh.

Sick LD is ready to stream/obtain scan profiles.

Definition at line 151 of file SickLD.hh.

const uint8_t SickToolbox::SickLD::SICK_WORK_SERV_TRANS_ROTATE = 0x03 [static]

Sick LD enters ROTATE mode (motor starts and rotates with a specified speed in Hz, laser is off)

Definition at line 142 of file SickLD.hh.


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


sicktoolbox
Author(s): Jason Derenick , Thomas Miller
autogenerated on Thu Aug 27 2015 15:17:16