Class SickSafetyscannersBase
Defined in File SickSafetyscanners.h
Inheritance Relationships
Derived Types
public sick::AsyncSickSafetyScanner
(Class AsyncSickSafetyScanner)public sick::SyncSickSafetyScanner
(Class SyncSickSafetyScanner)
Class Documentation
-
class SickSafetyscannersBase
Base class for the SICK safety scanners. This class provides a COLA2 API for the user and handles internally a COLA2 session and a UDP client for derived classes.
Subclassed by sick::AsyncSickSafetyScanner, sick::SyncSickSafetyScanner
Public Functions
-
SickSafetyscannersBase() = delete
Deleted default, copy and copy-assignment constructors.
-
SickSafetyscannersBase(const SickSafetyscannersBase&) = delete
-
SickSafetyscannersBase &operator=(const SickSafetyscannersBase&) = delete
-
SickSafetyscannersBase(sick::types::ip_address_t sensor_ip, sick::types::port_t sensor_tcp_port, CommSettings comm_settings, boost::asio::io_service &io_service)
Constructor of the SickSafetyscannersBase class.
- Parameters:
sensor_ip – The IP4 address of the sensor.
sensor_tcp_port – The TCP port of the sensor (COLA2).
comm_settings – A CommSettings object containing parameters to be sent to the sensor. The host (client) UDP port, if not available for allocation, might be overwritten by an automatically choosen one.
io_service – A boost::asio io_service instance used internally to manage sockets and threads. This constructor variant prevents creating an internal io_service and relies on the caller to perform run-calls and keep the io_service alive.
-
SickSafetyscannersBase(sick::types::ip_address_t sensor_ip, sick::types::port_t sensor_tcp_port, CommSettings comm_settings)
Constructor of the SickSafetyscannersBase class.
- Parameters:
sensor_ip – The IP4 address of the sensor.
sensor_tcp_port – The TCP port of the sensor (COLA2).
comm_settings – A CommSettings object containing parameters to be sent to the sensor. The host (client) UDP port, if not available for allocation, might be overwritten by an automatically choosen one.
-
SickSafetyscannersBase(sick::types::ip_address_t sensor_ip, sick::types::port_t sensor_tcp_port, CommSettings comm_settings, boost::asio::ip::address_v4 interface_ip)
Constructor of the SickSafetyscannersBase class.
- Parameters:
sensor_ip – The IP4 address of the sensor.
sensor_tcp_port – The TCP port of the sensor (COLA2).
comm_settings – A CommSettings object containing parameters to be sent to the sensor. The host (client) UDP port, if not available for allocation, might be overwritten by an automatically choosen one.
interface_ip – If multicast IP adresses are used for the host_ip, the corresponding interface of the host has to be defined for the socket to allow joining the multicast group.
-
void changeSensorSettings(const CommSettings &settings)
Virtual destructor of this base class.
Changes the internal settings of the sensor.
- Parameters:
settings – New set of settings to pass to the sensor.
-
void requestTypeCode(datastructure::TypeCode &type_code)
Requests the typecode of the sensor.
- Parameters:
type_code – Returned typecode.
-
void requestApplicationName(datastructure::ApplicationName &application_name)
Requests the application name from the sensor.
- Parameters:
application_name – Returned application name.
-
void requestSerialNumber(datastructure::SerialNumber &serial_number)
Requests the serial number of the sensor.
- Parameters:
serial_number – Returned serial number.
-
void requestFirmwareVersion(datastructure::FirmwareVersion &firmware_version)
Requests the firmware version of the sensor.
- Parameters:
firmware_version – Returned firmware version.
-
void requestOrderNumber(datastructure::OrderNumber &order_number)
Requests the order number of the sensor.
- Parameters:
order_number – Returned order number.
-
void requestProjectName(datastructure::ProjectName &project_name)
Requests the project name from the sensor.
- Parameters:
project_name – Returned project name.
-
void requestUserName(datastructure::UserName &user_name)
Requests the user name from the sensor.
- Parameters:
user_name – Returned user name.
-
void requestConfigMetadata(datastructure::ConfigMetadata &config_metadata)
Requests the config metadata from the sensor.
- Parameters:
config_metadata – Returned config metadata.
-
void requestStatusOverview(datastructure::StatusOverview &status_overview)
Request a status overview from the sensor.
- Parameters:
status_overview – Returned status overview.
-
void requestDeviceStatus(datastructure::DeviceStatus &device_status)
Requests the sensor’s device status (e.g. useful for monitoring errors).
- Parameters:
device_status – Returned device status.
-
void requestRequiredUserAction(datastructure::RequiredUserAction &required_user_action)
Requests the ‘required user action’ which provides along with device status information on troubleshooting.
- Parameters:
required_user_action – Returned required user action information.
-
void requestLatestTelegram(datastructure::Data &data, int8_t channel_index = 0)
Requests the latest sensor data telegram.
- Parameters:
data – Returned data.
channel_index – The channel index in the range of (0-3).
-
void findSensor(uint16_t blink_time)
Requests the sensor to let its display blink in various colors for the specified time.
- Parameters:
blink_time – The time of the display to blink [seconds].
-
void requestFieldData(std::vector<FieldData> &field_data)
Requests data of the protective and warning fields from the sensor.
- Parameters:
field_data – Returned field data.
-
void requestDeviceName(datastructure::DeviceName &device_name)
Requests the name of the device from the sensor.
- Parameters:
device_name – Returned device name.
-
void requestPersistentConfig(ConfigData &config_data)
Requests the persistent configuration from the sensor.
- Parameters:
config_data – Returned persistent configuration data.
-
void requestMonitoringCases(std::vector<MonitoringCaseData> &monitoring_cases)
Requests the monitoring cases from the sensor.
- Parameters:
monitoring_cases – Returned monitoring cases.
Protected Attributes
-
boost::asio::io_service &m_io_service
-
sick::cola2::Cola2Session m_session
-
sick::data_processing::UDPPacketMerger m_packet_merger
-
SickSafetyscannersBase() = delete