1 #ifndef TOPOSENS_ECHO_DRIVER_LIB_UTILS_H 2 #define TOPOSENS_ECHO_DRIVER_LIB_UTILS_H 14 void InitCanInterface(
const std::string& can_device,
int data_rate = 1000000);
57 void LogMsgCallback(uint16_t SenderId_u16, uint8_t* ReceivedPayload_pu8);
64 std::stringstream hex_ss;
65 hex_ss <<
"0x" << std::setfill(
'0') << std::setw(2) << std::uppercase << std::hex << i;
71 #endif // TOPOSENS_ECHO_DRIVER_LIB_UTILS_H void InitCanInterface(const std::string &can_device, int data_rate=1000000)
Inits the driver on given can_device with hard-coded data rate.
void LogKnownSensors(double log_interval=3.0)
Get currently known sensors from driver and log to ROS console every log_interval seconds...
void LogMsgCallback(uint16_t SenderId_u16, uint8_t *ReceivedPayload_pu8)
Callback handling log messages from sensor.
auto SetTargetSensor(uint16_t TargetSensor_u16) -> bool
Checks if TargetSensor_u16 is known and sets current target accordingly.
void LogSettings()
Read current configuration from sensor and log to ROS console.
void InitUARTInterface(const std::string &uart_device, int data_rate=0010002)
Inits the driver on given uart_device with hard-coded data rate.
void LogVersions()
Read all version information (such as bootloader version, app versionetc.) from sensor and log to ROS...
auto RequestSessionData() -> Sensor_Session_t *
Requesting single shot measurement from first sensor in known sensors array.
This file contains the highlevel interface prototypes to the low-level Protocol.
void DeinitCanInterface()
void DeinitUARTInterface()
void ConfigureSensorLogMessages(void(*Callback)(uint16_t Sender_u16, uint8_t *ReceivedPayload_pu8), LogLevel_t log_level)
Sets log level with the sensor and registers callback.
auto toHexString(const uint16_t i) -> std::string
Convert given i to hex string.
void LogSessionData(const Sensor_Session_t *session)
Log given session data to ROS concole.