SickSafetyscanners.cpp
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 
24 // -- END LICENSE BLOCK ------------------------------------------------
25 
26 //----------------------------------------------------------------------
33 //----------------------------------------------------------------------
34 
35 
37 
38 namespace sick {
39 
41  const packetReceivedCallbackFunction& newPacketReceivedCallbackFunction,
43  boost::asio::ip::address_v4 interface_ip)
44  : m_newPacketReceivedCallbackFunction(newPacketReceivedCallbackFunction)
45 {
46  ROS_INFO("Starting SickSafetyscanners");
47  m_io_service_ptr = std::make_shared<boost::asio::io_service>();
48  if (settings->getHostIp().is_multicast())
49  {
50  ROS_INFO("Multicast Host Ip configured");
51  m_async_udp_client_ptr = std::make_shared<sick::communication::AsyncUDPClient>(
52  boost::bind(&SickSafetyscanners::processUDPPacket, this, _1),
53  boost::ref(*m_io_service_ptr),
54  settings->getHostIp(),
55  // boost::asio::ip::address_v4::from_string("192.168.1.9"),
56  interface_ip,
57  settings->getHostUdpPort());
58  }
59  else
60  {
61  m_async_udp_client_ptr = std::make_shared<sick::communication::AsyncUDPClient>(
62  boost::bind(&SickSafetyscanners::processUDPPacket, this, _1),
63  boost::ref(*m_io_service_ptr),
64  settings->getHostUdpPort());
65  }
66  settings->setHostUdpPort(
68  ->getLocalPort()); // Store which port was used, needed for data request from the laser
69  m_packet_merger_ptr = std::make_shared<sick::data_processing::UDPPacketMerger>();
70  ROS_INFO("Started SickSafetyscanners");
71 }
72 
74 {
75  m_io_service_ptr->stop();
78 }
79 
81 {
83  new boost::thread(boost::bind(&SickSafetyscanners::udpClientThread, this)));
84 
85  m_async_udp_client_ptr->runService();
86  return true;
87 }
88 
90 {
91  ROS_INFO("Enter io thread");
92  m_io_work_ptr = std::make_shared<boost::asio::io_service::work>(boost::ref(*m_io_service_ptr));
93  m_io_service_ptr->run();
94  ROS_INFO("Exit io thread");
95  return true;
96 }
97 
98 
100 {
101  // Not needed for current functionality, inplace for possible future developments
102 }
103 
105 {
106  startTCPConnection(settings);
109 }
110 
112  uint16_t blink_time)
113 {
114  startTCPConnection(settings);
115  FindSensorInColaSession(blink_time);
117 }
118 
121 {
122  startTCPConnection(settings);
123  requestTypeCodeInColaSession(type_code);
125 }
126 
128  const datastructure::CommSettings& settings,
129  sick::datastructure::ApplicationName& application_name)
130 {
131  startTCPConnection(settings);
132  requestApplicationNameInColaSession(application_name);
134 }
136  std::vector<sick::datastructure::FieldData>& field_data)
137 {
138  startTCPConnection(settings);
139  requestFieldDataInColaSession(field_data);
141 }
142 
144  const datastructure::CommSettings& settings,
145  std::vector<sick::datastructure::MonitoringCaseData>& monitoring_cases)
146 {
147  startTCPConnection(settings);
148  requestMonitoringCaseDataInColaSession(monitoring_cases);
150 }
151 
153  datastructure::DeviceName& device_name)
154 {
155  startTCPConnection(settings);
156  requestDeviceNameInColaSession(device_name);
158 }
159 
161  datastructure::SerialNumber& serial_number)
162 {
163  startTCPConnection(settings);
164  requestSerialNumberInColaSession(serial_number);
166 }
167 
169  datastructure::OrderNumber& order_number)
170 {
171  startTCPConnection(settings);
172  requestOrderNumberInColaSession(order_number);
174 }
175 
177  datastructure::ProjectName& project_name)
178 {
179  startTCPConnection(settings);
180  requestProjectNameInColaSession(project_name);
182 }
183 
185  datastructure::UserName& user_name)
186 {
187  startTCPConnection(settings);
188  requestUserNameInColaSession(user_name);
190 }
192  datastructure::FirmwareVersion& firmware_version)
193 {
194  startTCPConnection(settings);
195  requestFirmwareVersionInColaSession(firmware_version);
197 }
198 
200  sick::datastructure::ConfigData& config_data)
201 {
202  startTCPConnection(settings);
205 }
206 
208  sick::datastructure::ConfigMetadata& config_metadata)
209 {
210  startTCPConnection(settings);
211  requestConfigMetadataInColaSession(config_metadata);
213 }
214 
216  sick::datastructure::StatusOverview& status_overview)
217 {
218  startTCPConnection(settings);
219  requestStatusOverviewInColaSession(status_overview);
221 }
222 
224  sick::datastructure::DeviceStatus& device_status)
225 {
226  startTCPConnection(settings);
227  requestDeviceStatusInColaSession(device_status);
229 }
230 
232  const datastructure::CommSettings& settings,
233  sick::datastructure::RequiredUserAction& required_user_action)
234 {
235  startTCPConnection(settings);
236  requestRequiredUserActionInColaSession(required_user_action);
238 }
239 
241 {
242  std::shared_ptr<sick::communication::AsyncTCPClient> async_tcp_client =
243  std::make_shared<sick::communication::AsyncTCPClient>(
244  boost::bind(&SickSafetyscanners::processTCPPacket, this, _1),
245  boost::ref(*m_io_service_ptr),
246  settings.getSensorIp(),
247  settings.getSensorTcpPort());
248  async_tcp_client->doConnect();
249 
250  m_session_ptr.reset();
251  m_session_ptr = std::make_shared<sick::cola2::Cola2Session>(async_tcp_client);
252 
253  m_session_ptr->open();
254 }
255 
257  const datastructure::CommSettings& settings)
258 {
260  std::make_shared<sick::cola2::ChangeCommSettingsCommand>(boost::ref(*m_session_ptr), settings);
261  m_session_ptr->executeCommand(command_ptr);
262 }
263 
265  std::vector<sick::datastructure::FieldData>& fields)
266 {
268 
269  for (int i = 0; i < 128; i++)
270  {
272 
273  command_ptr = std::make_shared<sick::cola2::FieldHeaderVariableCommand>(
274  boost::ref(*m_session_ptr), field_data, i);
275  m_session_ptr->executeCommand(command_ptr);
276 
277  if (field_data.getIsValid())
278  {
279  command_ptr = std::make_shared<sick::cola2::FieldGeometryVariableCommand>(
280  boost::ref(*m_session_ptr), field_data, i);
281  m_session_ptr->executeCommand(command_ptr);
282 
283  fields.push_back(field_data);
284  }
285  else if (i > 0) // index 0 is reserved for contour data
286  {
287  break; // skip other requests after first invalid
288  }
289  }
290 }
291 
293  std::vector<sick::datastructure::MonitoringCaseData>& monitoring_cases)
294 {
296  for (int i = 0; i < 254; i++)
297  {
298  sick::datastructure::MonitoringCaseData monitoring_case_data;
299 
300  command_ptr = std::make_shared<sick::cola2::MonitoringCaseVariableCommand>(
301  boost::ref(*m_session_ptr), monitoring_case_data, i);
302  m_session_ptr->executeCommand(command_ptr);
303  if (monitoring_case_data.getIsValid())
304  {
305  monitoring_cases.push_back(monitoring_case_data);
306  }
307  else
308  {
309  break; // skip other requests after first invalid
310  }
311  }
312 }
313 
315 {
317  std::make_shared<sick::cola2::FindMeCommand>(boost::ref(*m_session_ptr), blink_time);
318  m_session_ptr->executeCommand(command_ptr);
319 }
320 
322 {
324  std::make_shared<sick::cola2::DeviceNameVariableCommand>(boost::ref(*m_session_ptr),
325  device_name);
326  m_session_ptr->executeCommand(command_ptr);
327  ROS_INFO("Device name: %s", device_name.getDeviceName().c_str());
328 }
329 
330 
332  datastructure::ApplicationName& application_name)
333 {
335  std::make_shared<sick::cola2::ApplicationNameVariableCommand>(boost::ref(*m_session_ptr),
336  application_name);
337  m_session_ptr->executeCommand(command_ptr);
338  ROS_INFO("Application name: %s", application_name.getApplicationName().c_str());
339 }
340 
342  datastructure::SerialNumber& serial_number)
343 {
345  std::make_shared<sick::cola2::SerialNumberVariableCommand>(boost::ref(*m_session_ptr),
346  serial_number);
347  m_session_ptr->executeCommand(command_ptr);
348  ROS_INFO("Serial Number: %s", serial_number.getSerialNumber().c_str());
349 }
350 
352  datastructure::FirmwareVersion& firmware_version)
353 {
355  std::make_shared<sick::cola2::FirmwareVersionVariableCommand>(boost::ref(*m_session_ptr),
356  firmware_version);
357  m_session_ptr->executeCommand(command_ptr);
358  ROS_INFO("Firmware Version: %s", firmware_version.getFirmwareVersion().c_str());
359 }
360 
362 {
364  std::make_shared<sick::cola2::TypeCodeVariableCommand>(boost::ref(*m_session_ptr), type_code);
365  m_session_ptr->executeCommand(command_ptr);
366  ROS_INFO("Type Code: %s", type_code.getTypeCode().c_str());
367 }
368 
370  sick::datastructure::OrderNumber& order_number)
371 {
373  std::make_shared<sick::cola2::OrderNumberVariableCommand>(boost::ref(*m_session_ptr),
374  order_number);
375  m_session_ptr->executeCommand(command_ptr);
376  ROS_INFO("Order Number: %s", order_number.getOrderNumber().c_str());
377 }
378 
380  sick::datastructure::ProjectName& project_name)
381 {
383  std::make_shared<sick::cola2::ProjectNameVariableCommand>(boost::ref(*m_session_ptr),
384  project_name);
385  m_session_ptr->executeCommand(command_ptr);
386  ROS_INFO("Project Name: %s", project_name.getProjectName().c_str());
387 }
388 
390 {
392  std::make_shared<sick::cola2::UserNameVariableCommand>(boost::ref(*m_session_ptr), user_name);
393  m_session_ptr->executeCommand(command_ptr);
394  ROS_INFO("User Name: %s", user_name.getUserName().c_str());
395 }
396 
398  sick::datastructure::ConfigMetadata& config_metadata)
399 {
401  std::make_shared<sick::cola2::ConfigMetadataVariableCommand>(boost::ref(*m_session_ptr),
402  config_metadata);
403  m_session_ptr->executeCommand(command_ptr);
404 }
405 
407  sick::datastructure::StatusOverview& status_overview)
408 {
410  std::make_shared<sick::cola2::StatusOverviewVariableCommand>(boost::ref(*m_session_ptr),
411  status_overview);
412  m_session_ptr->executeCommand(command_ptr);
413 }
414 
416  sick::datastructure::DeviceStatus& device_status)
417 {
419  std::make_shared<sick::cola2::DeviceStatusVariableCommand>(boost::ref(*m_session_ptr),
420  device_status);
421  m_session_ptr->executeCommand(command_ptr);
422 }
423 
425  sick::datastructure::RequiredUserAction& required_user_action)
426 {
428  std::make_shared<sick::cola2::RequiredUserActionVariableCommand>(boost::ref(*m_session_ptr),
429  required_user_action);
430  m_session_ptr->executeCommand(command_ptr);
431 }
432 
434  sick::datastructure::ConfigData& config_data)
435 {
437  std::make_shared<sick::cola2::MeasurementPersistentConfigVariableCommand>(
438  boost::ref(*m_session_ptr), config_data);
439  m_session_ptr->executeCommand(command_ptr);
440 }
441 
443 {
444  m_session_ptr->close();
445  m_session_ptr->doDisconnect();
446 }
447 
448 
450 {
451  if (m_packet_merger_ptr->addUDPPacket(buffer))
452  {
453  sick::datastructure::PacketBuffer deployed_buffer =
454  m_packet_merger_ptr->getDeployedPacketBuffer();
456  sick::datastructure::Data data = data_parser.parseUDPSequence(deployed_buffer);
457 
459  }
460 }
461 
462 } // namespace sick
sick::cola2::Cola2Session::CommandPtr
std::shared_ptr< sick::cola2::Command > CommandPtr
Typedef for a pointer containing a command to be executed.
Definition: Cola2Session.h:78
sick::SickSafetyscanners::packetReceivedCallbackFunction
boost::function< void(const sick::datastructure::Data &)> packetReceivedCallbackFunction
Definition: SickSafetyscanners.h:90
sick::SickSafetyscanners::requestOrderNumber
void requestOrderNumber(const datastructure::CommSettings &settings, datastructure::OrderNumber &order_number)
Definition: SickSafetyscanners.cpp:168
sick::datastructure::ConfigMetadata
Class containing the serial number of a laser scanner.
Definition: ConfigMetadata.h:48
sick::SickSafetyscanners::requestPersistentConfigInColaSession
void requestPersistentConfigInColaSession(sick::datastructure::ConfigData &config_data)
Definition: SickSafetyscanners.cpp:433
sick::SickSafetyscanners::requestDeviceStatusInColaSession
void requestDeviceStatusInColaSession(sick::datastructure::DeviceStatus &device_status)
Definition: SickSafetyscanners.cpp:415
sick::SickSafetyscanners::stopTCPConnection
void stopTCPConnection()
Definition: SickSafetyscanners.cpp:442
sick::datastructure::OrderNumber
Class containing the order number of a laser scanner.
Definition: OrderNumber.h:47
sick::SickSafetyscanners::requestTypeCodeInColaSession
void requestTypeCodeInColaSession(sick::datastructure::TypeCode &type_code)
Definition: SickSafetyscanners.cpp:361
sick::datastructure::UserName
Class containing the user name of a laser scanner.
Definition: UserName.h:47
sick
Definition: ApplicationNameVariableCommand.h:43
sick::datastructure::FieldData
Field data for warning and protective fields.
Definition: FieldData.h:48
sick::datastructure::ApplicationName::getApplicationName
std::string getApplicationName() const
Gets the application name for the scanner.
Definition: ApplicationName.cpp:92
sick::SickSafetyscanners::processTCPPacket
void processTCPPacket(const sick::datastructure::PacketBuffer &buffer)
Definition: SickSafetyscanners.cpp:99
sick::datastructure::CommSettings
Containing the communication settings for the sensor which can be changed on runtime.
Definition: CommSettings.h:48
sick::datastructure::CommSettings::setHostUdpPort
void setHostUdpPort(const uint16_t &host_udp_port)
Sets the host udp port.
Definition: CommSettings.cpp:62
sick::SickSafetyscanners::startTCPConnection
void startTCPConnection(const sick::datastructure::CommSettings &settings)
Definition: SickSafetyscanners.cpp:240
sick::SickSafetyscanners::requestUserNameInColaSession
void requestUserNameInColaSession(sick::datastructure::UserName &user_name)
Definition: SickSafetyscanners.cpp:389
sick::datastructure::DeviceName
Class containing the device name of a laser scanner.
Definition: DeviceName.h:47
sick::SickSafetyscanners::requestFieldData
void requestFieldData(const sick::datastructure::CommSettings &settings, std::vector< sick::datastructure::FieldData > &field_data)
Requests data of the protective and warning fields from the sensor.
Definition: SickSafetyscanners.cpp:135
sick::SickSafetyscanners::changeCommSettingsInColaSession
void changeCommSettingsInColaSession(const datastructure::CommSettings &settings)
Definition: SickSafetyscanners.cpp:256
sick::SickSafetyscanners::m_async_udp_client_ptr
std::shared_ptr< sick::communication::AsyncUDPClient > m_async_udp_client_ptr
Definition: SickSafetyscanners.h:203
sick::SickSafetyscanners::FindSensorInColaSession
void FindSensorInColaSession(uint16_t blink_time)
Definition: SickSafetyscanners.cpp:314
sick::datastructure::Data
The data class containing all data blocks of a measurement.
Definition: Data.h:55
sick::SickSafetyscanners::changeSensorSettings
void changeSensorSettings(const sick::datastructure::CommSettings &settings)
Changes the internal settings of the sensor.
Definition: SickSafetyscanners.cpp:104
sick::SickSafetyscanners::requestStatusOverview
void requestStatusOverview(const datastructure::CommSettings &settings, datastructure::StatusOverview &status_overview)
Definition: SickSafetyscanners.cpp:215
sick::SickSafetyscanners::requestPersistentConfig
void requestPersistentConfig(const datastructure::CommSettings &settings, sick::datastructure::ConfigData &config_data)
Requests the persistent configuration from the sensor.
Definition: SickSafetyscanners.cpp:199
sick::datastructure::UserName::getUserName
std::string getUserName() const
Gets the user name for the scanner.
Definition: UserName.cpp:92
sick::SickSafetyscanners::requestProjectNameInColaSession
void requestProjectNameInColaSession(sick::datastructure::ProjectName &project_name)
Definition: SickSafetyscanners.cpp:379
data
data
sick::SickSafetyscanners::processUDPPacket
void processUDPPacket(const sick::datastructure::PacketBuffer &buffer)
Definition: SickSafetyscanners.cpp:449
sick::SickSafetyscanners::requestOrderNumberInColaSession
void requestOrderNumberInColaSession(sick::datastructure::OrderNumber &order_number)
Definition: SickSafetyscanners.cpp:369
sick::datastructure::SerialNumber::getSerialNumber
std::string getSerialNumber() const
Gets the serial number for the scanner.
Definition: SerialNumber.cpp:42
sick::datastructure::CommSettings::getHostUdpPort
uint16_t getHostUdpPort() const
Gets the host udp port.
Definition: CommSettings.cpp:57
sick::SickSafetyscanners::m_io_service_ptr
std::shared_ptr< boost::asio::io_service > m_io_service_ptr
Definition: SickSafetyscanners.h:201
sick::SickSafetyscanners::SickSafetyscanners
SickSafetyscanners(const packetReceivedCallbackFunction &newPacketReceivedCallbackFunction, sick::datastructure::CommSettings *settings, boost::asio::ip::address_v4 interface_ip)
Constructor of the SickSafetyscanners class.
Definition: SickSafetyscanners.cpp:40
sick::data_processing::ParseData
Parses the udp data packets depending on which data will be received.
Definition: ParseData.h:56
sick::datastructure::ProjectName::getProjectName
std::string getProjectName() const
Gets the project name for the scanner.
Definition: ProjectName.cpp:42
sick::SickSafetyscanners::m_udp_client_thread_ptr
boost::scoped_ptr< boost::thread > m_udp_client_thread_ptr
Definition: SickSafetyscanners.h:205
sick::SickSafetyscanners::requestTypeCode
void requestTypeCode(const sick::datastructure::CommSettings &settings, sick::datastructure::TypeCode &type_code)
Requests the typecode of the sensor.
Definition: SickSafetyscanners.cpp:119
sick::SickSafetyscanners::udpClientThread
bool udpClientThread()
Definition: SickSafetyscanners.cpp:89
sick::SickSafetyscanners::requestRequiredUserAction
void requestRequiredUserAction(const datastructure::CommSettings &settings, datastructure::RequiredUserAction &required_user_action)
Definition: SickSafetyscanners.cpp:231
sick::datastructure::ApplicationName
Class containing the application name of a laser scanner.
Definition: ApplicationName.h:47
sick::datastructure::CommSettings::getSensorTcpPort
uint16_t getSensorTcpPort() const
Gets the sensor tcp port.
Definition: CommSettings.cpp:166
sick::SickSafetyscanners::requestRequiredUserActionInColaSession
void requestRequiredUserActionInColaSession(sick::datastructure::RequiredUserAction &required_user_action)
Definition: SickSafetyscanners.cpp:424
sick::SickSafetyscanners::run
bool run()
Start the connection to the sensor and enables output.
Definition: SickSafetyscanners.cpp:80
sick::datastructure::StatusOverview
Class containing the serial number of a laser scanner.
Definition: StatusOverview.h:47
sick::datastructure::OrderNumber::getOrderNumber
std::string getOrderNumber() const
Gets the order number for the scanner.
Definition: OrderNumber.cpp:42
sick::datastructure::TypeCode::getTypeCode
std::string getTypeCode() const
Gets the type code for the scanner.
Definition: TypeCode.cpp:42
sick::data_processing::ParseData::parseUDPSequence
sick::datastructure::Data parseUDPSequence(const sick::datastructure::PacketBuffer &buffer) const
Parses the udp data transferred in the packet buffer. It will be parsed into the data reference.
Definition: ParseData.cpp:52
sick::datastructure::RequiredUserAction
Class containing the additional information about the sopas state.
Definition: RequiredUserAction.h:47
sick::SickSafetyscanners::requestDeviceNameInColaSession
void requestDeviceNameInColaSession(datastructure::DeviceName &device_name)
Definition: SickSafetyscanners.cpp:321
sick::SickSafetyscanners::requestFirmwareVersionInColaSession
void requestFirmwareVersionInColaSession(sick::datastructure::FirmwareVersion &firmware_version)
Definition: SickSafetyscanners.cpp:351
sick::SickSafetyscanners::requestSerialNumberInColaSession
void requestSerialNumberInColaSession(sick::datastructure::SerialNumber &serial_number)
Definition: SickSafetyscanners.cpp:341
sick::SickSafetyscanners::requestConfigMetadataInColaSession
void requestConfigMetadataInColaSession(sick::datastructure::ConfigMetadata &config_metadata)
Definition: SickSafetyscanners.cpp:397
sick::SickSafetyscanners::requestMonitoringCaseDataInColaSession
void requestMonitoringCaseDataInColaSession(std::vector< sick::datastructure::MonitoringCaseData > &monitoring_cases)
Definition: SickSafetyscanners.cpp:292
sick::SickSafetyscanners::FindSensor
void FindSensor(const datastructure::CommSettings &settings, uint16_t blink_time)
Definition: SickSafetyscanners.cpp:111
sick::SickSafetyscanners::~SickSafetyscanners
virtual ~SickSafetyscanners()
Destructor.
Definition: SickSafetyscanners.cpp:73
sick::datastructure::ProjectName
Class containing the project name of a laser scanner.
Definition: ProjectName.h:47
sick::SickSafetyscanners::m_session_ptr
std::shared_ptr< sick::cola2::Cola2Session > m_session_ptr
Definition: SickSafetyscanners.h:207
sick::datastructure::SerialNumber
Class containing the serial number of a laser scanner.
Definition: SerialNumber.h:47
sick::datastructure::DeviceStatus
Class containing the device status of a laser scanner.
Definition: DeviceStatus.h:47
sick::datastructure::FieldData::getIsValid
bool getIsValid() const
Returns if the received field data is valid.
Definition: FieldData.cpp:42
sick::SickSafetyscanners::m_newPacketReceivedCallbackFunction
packetReceivedCallbackFunction m_newPacketReceivedCallbackFunction
Definition: SickSafetyscanners.h:199
sick::SickSafetyscanners::requestApplicationName
void requestApplicationName(const sick::datastructure::CommSettings &settings, sick::datastructure::ApplicationName &application_name)
Definition: SickSafetyscanners.cpp:127
sick::SickSafetyscanners::requestStatusOverviewInColaSession
void requestStatusOverviewInColaSession(sick::datastructure::StatusOverview &status_overview)
Definition: SickSafetyscanners.cpp:406
sick::SickSafetyscanners::requestFieldDataInColaSession
void requestFieldDataInColaSession(std::vector< sick::datastructure::FieldData > &fields)
Definition: SickSafetyscanners.cpp:264
sick::datastructure::ConfigData
Config data for current and persistent sensor config.
Definition: ConfigData.h:50
sick::SickSafetyscanners::requestDeviceName
void requestDeviceName(const sick::datastructure::CommSettings &settings, datastructure::DeviceName &device_name)
Requests the name of the device from the sensor.
Definition: SickSafetyscanners.cpp:152
sick::datastructure::CommSettings::getHostIp
boost::asio::ip::address_v4 getHostIp() const
Gets the IP-address of the host.
Definition: CommSettings.cpp:42
sick::SickSafetyscanners::requestFirmwareVersion
void requestFirmwareVersion(const sick::datastructure::CommSettings &settings, sick::datastructure::FirmwareVersion &firmware_version)
Requests the firmware version of the sensor.
Definition: SickSafetyscanners.cpp:191
sick::SickSafetyscanners::requestDeviceStatus
void requestDeviceStatus(const datastructure::CommSettings &settings, datastructure::DeviceStatus &device_status)
Definition: SickSafetyscanners.cpp:223
sick::datastructure::MonitoringCaseData::getIsValid
bool getIsValid() const
Returns if the received monitoring case data is valid.
Definition: MonitoringCaseData.cpp:42
sick::datastructure::MonitoringCaseData
Stores the data for the different monitoring cases.
Definition: MonitoringCaseData.h:48
sick::SickSafetyscanners::requestUserName
void requestUserName(const datastructure::CommSettings &settings, datastructure::UserName &user_name)
Definition: SickSafetyscanners.cpp:184
sick::datastructure::PacketBuffer
A packetbuffer for the raw data from the sensor.
Definition: PacketBuffer.h:61
sick::datastructure::TypeCode
Class containing the type code of a laser scanner.
Definition: TypeCode.h:62
sick::SickSafetyscanners::m_io_work_ptr
std::shared_ptr< boost::asio::io_service::work > m_io_work_ptr
Definition: SickSafetyscanners.h:202
ROS_INFO
#define ROS_INFO(...)
sick::datastructure::FirmwareVersion
Class containing the firmware version of a laser scanner.
Definition: FirmwareVersion.h:47
sick::SickSafetyscanners::requestSerialNumber
void requestSerialNumber(const sick::datastructure::CommSettings &settings, sick::datastructure::SerialNumber &serial_number)
Definition: SickSafetyscanners.cpp:160
sick::SickSafetyscanners::requestMonitoringCases
void requestMonitoringCases(const sick::datastructure::CommSettings &settings, std::vector< sick::datastructure::MonitoringCaseData > &monitoring_cases)
Requests the monitoring cases from the sensor.
Definition: SickSafetyscanners.cpp:143
sick::SickSafetyscanners::requestProjectName
void requestProjectName(const datastructure::CommSettings &settings, datastructure::ProjectName &project_name)
Definition: SickSafetyscanners.cpp:176
sick::SickSafetyscanners::requestApplicationNameInColaSession
void requestApplicationNameInColaSession(sick::datastructure::ApplicationName &application_name)
Definition: SickSafetyscanners.cpp:331
sick::SickSafetyscanners::requestConfigMetadata
void requestConfigMetadata(const datastructure::CommSettings &settings, datastructure::ConfigMetadata &config_metadata)
Requests the config meta data of the sensor.
Definition: SickSafetyscanners.cpp:207
sick::SickSafetyscanners::m_packet_merger_ptr
std::shared_ptr< sick::data_processing::UDPPacketMerger > m_packet_merger_ptr
Definition: SickSafetyscanners.h:209
sick::datastructure::CommSettings::getSensorIp
boost::asio::ip::address_v4 getSensorIp() const
Gets the sensor IP-address.
Definition: CommSettings.cpp:151
SickSafetyscanners.h
sick::datastructure::FirmwareVersion::getFirmwareVersion
std::string getFirmwareVersion() const
Gets the firmware version for the scanner.
Definition: FirmwareVersion.cpp:42
sick::datastructure::DeviceName::getDeviceName
std::string getDeviceName() const
Gets the device name for the scanner.
Definition: DeviceName.cpp:42


sick_safetyscanners
Author(s): Lennart Puck
autogenerated on Fri Jun 21 2024 02:40:51