Classes | Typedefs | Functions
toposens_echo_driver Namespace Reference

Classes

class  EchoOneDriver
 
class  RosParameters
 

Typedefs

using EchoOneDriverConfigServer = dynamic_reconfigure::Server< EchoOneDriverConfig >
 

Functions

void adcDumpEndCallback (uint16_t sender_id)
 Callback for device driver library. More...
 
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. More...
 
void DeinitCanInterface ()
 
void DeinitUARTInterface ()
 
auto getStaticTransformMsg (const ros::Time &t, const std::vector< float > &trans, const tf::Quaternion &q, const std::string &from, const std::string &to) -> geometry_msgs::TransformStamped
 Returns geometry_msgs::TransformStamped to be published by TF broadcaster. More...
 
void InitCanInterface (const std::string &can_device, int data_rate=1000000)
 Inits the driver on given can_device with hard-coded data rate. More...
 
void InitUARTInterface (const std::string &uart_device, int data_rate=0010002)
 Inits the driver on given uart_device with hard-coded data rate. More...
 
void LogMsgCallback (uint16_t SenderId_u16, uint8_t *ReceivedPayload_pu8)
 Callback handling log messages from sensor. More...
 
bool requestAdcDump (RequestAdcDump::Request &req, RequestAdcDump::Response &res)
 ROS Service Callback for ADC Dump Requests. More...
 
void requestAdcDumpCallback (uint16_t sender_id, uint32_t data_size)
 Callback for device driver library. More...
 
auto RequestSessionData () -> Sensor_Session_t *
 Requesting single shot measurement from first sensor in known sensors array. More...
 
auto saveAdcBlobData (ADCDump_t *adc_dump, const char *file_path) -> bool
 Saves given adc_dump to file file_path. More...
 
auto SetTargetSensor (uint16_t TargetSensor_u16) -> bool
 Checks if TargetSensor_u16 is known and sets current target accordingly. More...
 
auto to_TsScan (const Sensor_Session_t *session_data, const RosParameters &params) -> toposens_msgs::TsScan
 Converts all points availabble in session_data to ROS message. More...
 
auto toHexString (const uint16_t i) -> std::string
 Convert given i to hex string. More...
 

Typedef Documentation

◆ EchoOneDriverConfigServer

using toposens_echo_driver::EchoOneDriverConfigServer = typedef dynamic_reconfigure::Server<EchoOneDriverConfig>

Definition at line 20 of file echo_driver.h.

Function Documentation

◆ adcDumpEndCallback()

void toposens_echo_driver::adcDumpEndCallback ( uint16_t  sender_id)

Callback for device driver library.

Simply acknowledging

Definition at line 94 of file adc_dump.cpp.

◆ ConfigureSensorLogMessages()

void toposens_echo_driver::ConfigureSensorLogMessages ( void(*)(uint16_t Sender_u16, uint8_t *ReceivedPayload_pu8)  Callback,
LogLevel_t  log_level = LOG_LEVEL_INFO 
)

Sets log level with the sensor and registers callback.

Definition at line 202 of file lib_utils.cpp.

◆ DeinitCanInterface()

void toposens_echo_driver::DeinitCanInterface ( )

Definition at line 13 of file lib_utils.cpp.

◆ DeinitUARTInterface()

void toposens_echo_driver::DeinitUARTInterface ( )

Definition at line 20 of file lib_utils.cpp.

◆ getStaticTransformMsg()

auto toposens_echo_driver::getStaticTransformMsg ( const ros::Time t,
const std::vector< float > &  trans,
const tf::Quaternion q,
const std::string &  from,
const std::string &  to 
) -> geometry_msgs::TransformStamped

Returns geometry_msgs::TransformStamped to be published by TF broadcaster.

Take transformation arguments (translation/rotation) and the corresponding frame ids and create the TF message to be published.

Definition at line 86 of file ros_utils.cpp.

◆ InitCanInterface()

void toposens_echo_driver::InitCanInterface ( const std::string &  can_device,
int  data_rate = 1000000 
)

Inits the driver on given can_device with hard-coded data rate.

Definition at line 8 of file lib_utils.cpp.

◆ InitUARTInterface()

void toposens_echo_driver::InitUARTInterface ( const std::string &  uart_device,
int  data_rate = 0010002 
)

Inits the driver on given uart_device with hard-coded data rate.

Definition at line 15 of file lib_utils.cpp.

◆ LogKnownSensors()

void toposens_echo_driver::LogKnownSensors ( double  log_interval = 3.0)

Get currently known sensors from driver and log to ROS console every log_interval seconds.

Definition at line 96 of file lib_utils.cpp.

◆ LogMsgCallback()

void toposens_echo_driver::LogMsgCallback ( uint16_t  SenderId_u16,
uint8_t *  ReceivedPayload_pu8 
)

Callback handling log messages from sensor.

Definition at line 216 of file lib_utils.cpp.

◆ LogSessionData()

void toposens_echo_driver::LogSessionData ( const Sensor_Session_t session)

Log given session data to ROS concole.

Logs all 1D as well as all 3D Points

Definition at line 148 of file lib_utils.cpp.

◆ LogSettings()

void toposens_echo_driver::LogSettings ( )

Read current configuration from sensor and log to ROS console.

Group of functions to log information to ROS console.

Definition at line 54 of file lib_utils.cpp.

◆ LogVersions()

void toposens_echo_driver::LogVersions ( )

Read all version information (such as bootloader version, app versionetc.) from sensor and log to ROS console.

Definition at line 123 of file lib_utils.cpp.

◆ requestAdcDump()

auto toposens_echo_driver::requestAdcDump ( RequestAdcDump::Request &  req,
RequestAdcDump::Response &  res 
)

ROS Service Callback for ADC Dump Requests.

Performs necessary steps to obtain ADC Dump from sensor. Utilizing the device driver library.

Returns
true if successful, false otherwise

Definition at line 9 of file adc_dump.cpp.

◆ requestAdcDumpCallback()

void toposens_echo_driver::requestAdcDumpCallback ( uint16_t  sender_id,
uint32_t  data_size 
)

Callback for device driver library.

Simply acknowledging

Definition at line 92 of file adc_dump.cpp.

◆ RequestSessionData()

auto toposens_echo_driver::RequestSessionData ( ) -> Sensor_Session_t*

Requesting single shot measurement from first sensor in known sensors array.

This is a blocking call!

Definition at line 22 of file lib_utils.cpp.

◆ saveAdcBlobData()

auto toposens_echo_driver::saveAdcBlobData ( ADCDump_t adc_dump,
const char *  file_path 
) -> bool

Saves given adc_dump to file file_path.

This was directly copied from an example application in the driver library. It should be updated to our C++ coding guidelines, possibly when the TODO in the code is addressed.

Returns
true if successful, false otherwise

Definition at line 59 of file adc_dump.cpp.

◆ to_TsScan()

auto toposens_echo_driver::to_TsScan ( const Sensor_Session_t session_data,
const RosParameters params 
) -> toposens_msgs::TsScan

Converts all points availabble in session_data to ROS message.

Based on coordinate frame defintion from here (Toposens) https://teamtoposens.atlassian.net/wiki/spaces/EN/pages/467697939/Standardized+Coordinate+System and here (ROS) https://www.ros.org/reps/rep-0103.html#axis-orientation.

Definition at line 55 of file ros_utils.cpp.

◆ toHexString()

auto toposens_echo_driver::toHexString ( const uint16_t  i) -> std::string
inline

Convert given i to hex string.

Note
Don't be tempted to change the parameter type to uint8_t!
Todo:
Potentially move this even to a separate utils header

Definition at line 62 of file lib_utils.h.



toposens_echo_driver
Author(s): Tobias Roth , Dennis Maier , Baris Yazici
autogenerated on Wed Mar 2 2022 01:12:32