Go to the documentation of this file.
7 #include "toposens_msgs/TsScan.h"
12 : nh_(nh), parameters_(
std::move(parameters))
14 ROS_INFO(
"Instantiating EchoOneDriver!");
32 ROS_DEBUG(
"EchoOneDriver: Initializing!");
46 throw std::invalid_argument(
"Unsupported communication interface");
56 ROS_INFO(
"Successfully configured sensor mode SENSOR_MODE_SINGLE_SHOT_TRANSMIT_LISTEN!");
60 ROS_WARN(
"Start SENSOR_MODE_SINGLE_SHOT_TRANSMIT_LISTEN did not work!");
64 constexpr
auto queue_size = 100;
78 ROS_ERROR(
"No sensors on bus, cannot measure!");
94 const auto target_frame_optical_frame = target_frame +
"_optical_frame";
96 auto zero_transform = {0.0F, 0.0F, 0.0F};
101 q_optical.
setRPY(-M_PI / 2.0, 0.0, -M_PI / 2.0);
105 target_frame_optical_frame);
116 ROS_DEBUG(
"Preparing dynamic reconfigure server...");
121 EchoOneDriverConfig initial_config;
128 [
this](
auto& config,
auto level) {
return reconfigure(config, level); });
133 auto log_reconfigure_failure = [](
const std::string& parameter_name) {
134 ROS_WARN(
"Reconfiguring of parameter %s failed!", parameter_name.c_str());
143 config.transducer_volume);
155 ROS_INFO(
"Successfully reconfigured %s to %d",
180 ROS_WARN(
"Unknown reconfigure level: %d!", level);
boost::recursive_mutex dynamic_reconfigure_server_mutex_
void measure()
Triggers single-shot measurement from sensor and publishes TsScan ROS message with result.
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
bool requestAdcDump(RequestAdcDump::Request &req, RequestAdcDump::Response &res)
ROS Service Callback for ADC Dump Requests.
void InitCanInterface(const std::string &can_device, int data_rate=1000000)
Inits the driver on given can_device with hard-coded data rate.
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
void requestAdcDumpCallback(uint16_t sender_id, uint32_t data_size)
Callback for device driver library.
void adcDumpEndCallback(uint16_t sender_id)
Callback for device driver library.
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
ros::Publisher ts_scan_publisher_
std::string com_interface
bool SetParameterTransducerVolume(uint8_t Volume_u8)
Blocking Request to set the Transducer Volume for current target sensor.
const std::string transducer_num_pulses_str
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.
bool SetParameterTransducerNumOfPulses(uint8_t NumOfPulses_u8)
Blocking Request to set the Number of Transducer Pulses for current target sensor.
void DeinitUARTInterface()
void LogVersions()
Read all version information (such as bootloader version, app versionetc.) from sensor and log to ROS...
uint8_t GetNumberOfKnownSensors()
Returns number of known sensors. With GetKnownSensors() users an pointer to an array containing the I...
void RegisterADCDumpSessionEndCallback(void(*Callback)(uint16_t Sender_u16))
Interface function to register a callback function that is called whenever an SessionEnd Payload for ...
EchoOneDriver(ros::NodeHandle nh, RosParameters parameters)
auto to_TsScan(const Sensor_Session_t *session_data, const RosParameters ¶ms) -> toposens_msgs::TsScan
Converts all points availabble in session_data to ROS message.
void DeinitCanInterface()
const std::string temperature_str
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.
@ SENSOR_MODE_SINGLE_SHOT_TRANSMIT_LISTEN
std::unique_ptr< EchoOneDriverConfigServer > dynamic_reconfigure_server_
void LogMsgCallback(uint16_t SenderId_u16, uint8_t *ReceivedPayload_pu8)
Callback handling log messages from sensor.
RosParameters parameters_
bool SetParameterSystemSensorMode(SensorMode_t Mode_t)
Blocking Request to set the Sensor Mode for current target sensor.
void reconfigure(const EchoOneDriverConfig &config, uint32_t level)
void configureDynamicReconfigureServer()
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.
int transducer_num_pulses
ros::ServiceServer adc_dump_service_
const std::string transducer_volume_str
void publishStaticTransforms()
Publish static TFs between sensor coordinate frames.
void RegisterADCDumpStartRequestCallback(void(*Callback)(uint16_t Sender_u16, uint32_t ADCDumpSize_32))
Interface function to register a callback function that is called whenever an ADC-Dump Start Payload ...
auto RequestSessionData() -> Sensor_Session_t *
Requesting single shot measurement from first sensor in known sensors array.
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
bool SetParameterSignalProcessingTemperature(float Temperature_f)
Blocking Request to set the Temperature for current target sensor.
toposens_echo_driver
Author(s): Tobias Roth
, Dennis Maier , Baris Yazici
autogenerated on Wed Mar 2 2022 01:12:32