Public Member Functions | Public Attributes | Static Public Attributes | List of all members
AS::Drivers::Ibeo::ErrorWarning Class Reference

#include <ibeo_core.h>

Inheritance diagram for AS::Drivers::Ibeo::ErrorWarning:
Inheritance graph
[legend]

Public Member Functions

void parse (const std::vector< uint8_t > &in)
 
- Public Member Functions inherited from AS::Drivers::Ibeo::IbeoTxMessage
virtual std::vector< Point3Dget_contour_points ()
 
virtual std::vector< IbeoObjectget_objects ()
 
virtual std::vector< Point3DLget_scan_points ()
 
 IbeoTxMessage ()
 
 IbeoTxMessage (bool scan_points, bool contour_points, bool objects)
 

Public Attributes

bool err_apd_over_temperature
 
bool err_apd_temperature_sensor_defect
 
bool err_apd_under_temperature
 
bool err_buffer_error_overflow
 
bool err_buffer_error_xmt_incomplete
 
bool err_config_contains_incorrect_params
 
bool err_config_fpga_not_configurable
 
bool err_config_incorrect_config_data
 
bool err_int_communication_error
 
bool err_int_incorrect_scan_data
 
bool err_int_no_scan_data
 
bool err_internal_error
 
bool err_motor_1_fault
 
bool err_motor_2_fault
 
bool err_motor_3_fault
 
bool err_motor_4_fault
 
bool err_motor_5_fault
 
bool err_timeout_data_processing
 
bool err_timeout_env_model_computation_reset
 
bool wrn_can_interface_blocked
 
bool wrn_ego_motion_data_missing
 
bool wrn_eth_interface_blocked
 
bool wrn_eth_unkwn_incomplete_data
 
bool wrn_high_temperature
 
bool wrn_incorrect_can_data_rcvd
 
bool wrn_incorrect_mounting_params
 
bool wrn_incorrect_or_forbidden_cmd_rcvd
 
bool wrn_int_communication_error
 
bool wrn_int_incorrect_scan_data
 
bool wrn_int_motor_1
 
bool wrn_int_overflow
 
bool wrn_laser_1_start_pulse_missing
 
bool wrn_laser_2_start_pulse_missing
 
bool wrn_low_temperature
 
bool wrn_memory_access_failure
 
bool wrn_no_obj_comp_due_to_scan_freq
 
bool wrn_sync_error
 
- Public Attributes inherited from AS::Drivers::Ibeo::IbeoTxMessage
uint16_t data_type
 
bool has_contour_points
 
bool has_objects
 
bool has_scan_points
 
IbeoDataHeader ibeo_header
 

Static Public Attributes

static const int32_t DATA_TYPE = 0x2030
 

Additional Inherited Members

- Static Public Member Functions inherited from AS::Drivers::Ibeo::IbeoTxMessage
static std::shared_ptr< IbeoTxMessagemake_message (const uint16_t &data_type)
 

Detailed Description

Definition at line 619 of file ibeo_core.h.

Member Function Documentation

void ErrorWarning::parse ( const std::vector< uint8_t > &  in)
virtual

Implements AS::Drivers::Ibeo::IbeoTxMessage.

Definition at line 594 of file ibeo_core.cpp.

Member Data Documentation

const int32_t AS::Drivers::Ibeo::ErrorWarning::DATA_TYPE = 0x2030
static

Definition at line 622 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_apd_over_temperature

Definition at line 628 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_apd_temperature_sensor_defect

Definition at line 630 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_apd_under_temperature

Definition at line 629 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_buffer_error_overflow

Definition at line 627 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_buffer_error_xmt_incomplete

Definition at line 626 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_config_contains_incorrect_params

Definition at line 640 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_config_fpga_not_configurable

Definition at line 638 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_config_incorrect_config_data

Definition at line 639 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_int_communication_error

Definition at line 636 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_int_incorrect_scan_data

Definition at line 637 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_int_no_scan_data

Definition at line 635 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_internal_error

Definition at line 624 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_motor_1_fault

Definition at line 625 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_motor_2_fault

Definition at line 631 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_motor_3_fault

Definition at line 632 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_motor_4_fault

Definition at line 633 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_motor_5_fault

Definition at line 634 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_timeout_data_processing

Definition at line 641 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::err_timeout_env_model_computation_reset

Definition at line 642 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_can_interface_blocked

Definition at line 650 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_ego_motion_data_missing

Definition at line 658 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_eth_interface_blocked

Definition at line 651 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_eth_unkwn_incomplete_data

Definition at line 654 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_high_temperature

Definition at line 645 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_incorrect_can_data_rcvd

Definition at line 652 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_incorrect_mounting_params

Definition at line 659 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_incorrect_or_forbidden_cmd_rcvd

Definition at line 655 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_int_communication_error

Definition at line 643 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_int_incorrect_scan_data

Definition at line 653 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_int_motor_1

Definition at line 646 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_int_overflow

Definition at line 657 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_laser_1_start_pulse_missing

Definition at line 648 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_laser_2_start_pulse_missing

Definition at line 649 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_low_temperature

Definition at line 644 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_memory_access_failure

Definition at line 656 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_no_obj_comp_due_to_scan_freq

Definition at line 660 of file ibeo_core.h.

bool AS::Drivers::Ibeo::ErrorWarning::wrn_sync_error

Definition at line 647 of file ibeo_core.h.


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


ibeo_core
Author(s): Joshua Whitley , Daniel Stanek
autogenerated on Fri Jun 7 2019 21:53:43