echo_driver.cpp
Go to the documentation of this file.
2 
3 #include <ros/ros.h>
4 
7 #include "toposens_msgs/TsScan.h"
8 
9 namespace toposens_echo_driver
10 {
12  : nh_(nh), parameters_(std::move(parameters))
13 {
14  ROS_INFO("Instantiating EchoOneDriver!");
15  initialize();
16 }
17 
19 {
20  if (parameters_.com_interface == "CAN")
21  {
23  }
24  else if (parameters_.com_interface == "UART")
25  {
27  }
28 }
29 
31 {
32  ROS_DEBUG("EchoOneDriver: Initializing!");
33 
34  // Prepare sensor communication
35  if (parameters_.com_interface == "CAN")
36  {
38  }
39  else if (parameters_.com_interface == "UART")
40  {
42  }
43  else
44  {
45  ROS_ERROR("Unsupported communication interface %s ", parameters_.com_interface.c_str());
46  throw std::invalid_argument("Unsupported communication interface");
47  }
48 
49  LogSettings();
50  LogVersions();
52 
53  // Prepare Single Measurement mode
55  {
56  ROS_INFO("Successfully configured sensor mode SENSOR_MODE_SINGLE_SHOT_TRANSMIT_LISTEN!");
57  }
58  else
59  {
60  ROS_WARN("Start SENSOR_MODE_SINGLE_SHOT_TRANSMIT_LISTEN did not work!");
61  }
62 
63  // Prepare publishers
64  constexpr auto queue_size = 100;
65  ts_scan_publisher_ = nh_.advertise<toposens_msgs::TsScan>(parameters_.scans_topic, queue_size);
66 
68 
69  adc_dump_service_ = nh_.advertiseService("request_adc_dump", &requestAdcDump);
72 }
73 
75 {
76  if (GetNumberOfKnownSensors() < 1)
77  {
78  ROS_ERROR("No sensors on bus, cannot measure!");
79  return;
80  }
81 
82  const auto* session_data = RequestSessionData();
83 
84  const auto msg = to_TsScan(session_data, parameters_);
86 }
87 
89 {
90  const auto ts = ros::Time::now();
91 
92  const auto base_frame = parameters_.frame_id;
93  const auto target_frame = parameters_.target_frame;
94  const auto target_frame_optical_frame = target_frame + "_optical_frame";
95 
96  auto zero_transform = {0.0F, 0.0F, 0.0F};
97 
99  q.setRPY(0, 0, 0);
100  tf::Quaternion q_optical;
101  q_optical.setRPY(-M_PI / 2.0, 0.0, -M_PI / 2.0);
102 
103  const auto tf_msg = getStaticTransformMsg(ts, zero_transform, q, base_frame, target_frame);
104  const auto tf_optical_msg = getStaticTransformMsg(ts, zero_transform, q_optical, target_frame,
105  target_frame_optical_frame);
106 
108  static_tf_broadcaster_.sendTransform(tf_optical_msg);
109 }
110 
112 {
113  // Set up dynamic reconfigure server
114  // Set values from config file (otherwise the dynamic reconfigure values would be set in
115  // rqt_reconfigure initially)
116  ROS_DEBUG("Preparing dynamic reconfigure server...");
117 
118  dynamic_reconfigure_server_ = std::make_unique<EchoOneDriverConfigServer>(
120 
121  EchoOneDriverConfig initial_config;
122  initial_config.transducer_volume = parameters_.transducer_volume;
123  initial_config.transducer_num_pulses = parameters_.transducer_num_pulses;
124  initial_config.temperature = parameters_.temperature;
125  dynamic_reconfigure_server_->updateConfig(initial_config);
126 
127  dynamic_reconfigure_server_->setCallback(
128  [this](auto& config, auto level) { return reconfigure(config, level); });
129 }
130 
131 void EchoOneDriver::reconfigure(const EchoOneDriverConfig& config, const uint32_t level)
132 {
133  auto log_reconfigure_failure = [](const std::string& parameter_name) {
134  ROS_WARN("Reconfiguring of parameter %s failed!", parameter_name.c_str());
135  };
136 
137  switch (level)
138  {
139  case 1: {
140  if (SetParameterTransducerVolume(static_cast<uint8_t>(config.transducer_volume)))
141  {
142  ROS_INFO("Successfully reconfigured %s to %d", parameters_.transducer_volume_str.c_str(),
143  config.transducer_volume);
144  }
145  else
146  {
147  log_reconfigure_failure(parameters_.transducer_volume_str);
148  }
149  break;
150  }
151 
152  case 2: {
153  if (SetParameterTransducerNumOfPulses(static_cast<uint8_t>(config.transducer_num_pulses)))
154  {
155  ROS_INFO("Successfully reconfigured %s to %d",
156  parameters_.transducer_num_pulses_str.c_str(), config.transducer_num_pulses);
157  }
158  else
159  {
160  log_reconfigure_failure(parameters_.transducer_num_pulses_str);
161  }
162  break;
163  }
164 
165  // NOLINTNEXTLINE (cppcoreguidelines-avoid-magic-numbers)
166  case 11: {
167  if (SetParameterSignalProcessingTemperature(static_cast<float>(config.temperature)))
168  {
169  ROS_INFO("Successfully reconfigured %s to %f", parameters_.temperature_str.c_str(),
170  config.temperature);
171  }
172  else
173  {
174  log_reconfigure_failure(parameters_.temperature_str);
175  }
176  break;
177  }
178 
179  default:
180  ROS_WARN("Unknown reconfigure level: %d!", level);
181  break;
182  }
183 }
184 
185 } // namespace toposens_echo_driver
toposens_echo_driver::RosParameters
Definition: ros_utils.h:17
toposens_echo_driver::RosParameters::target_frame
std::string target_frame
Definition: ros_utils.h:26
tf2_ros::StaticTransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
toposens_echo_driver::EchoOneDriver::dynamic_reconfigure_server_mutex_
boost::recursive_mutex dynamic_reconfigure_server_mutex_
Definition: echo_driver.h:51
toposens_echo_driver::EchoOneDriver::measure
void measure()
Triggers single-shot measurement from sensor and publishes TsScan ROS message with result.
Definition: echo_driver.cpp:74
tf::Quaternion::setRPY
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
toposens_echo_driver::requestAdcDump
bool requestAdcDump(RequestAdcDump::Request &req, RequestAdcDump::Response &res)
ROS Service Callback for ADC Dump Requests.
Definition: adc_dump.cpp:9
lib_utils.h
ros.h
toposens_echo_driver::InitCanInterface
void InitCanInterface(const std::string &can_device, int data_rate=1000000)
Inits the driver on given can_device with hard-coded data rate.
Definition: lib_utils.cpp:8
toposens_echo_driver::EchoOneDriver::nh_
ros::NodeHandle nh_
Definition: echo_driver.h:44
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
toposens_echo_driver::requestAdcDumpCallback
void requestAdcDumpCallback(uint16_t sender_id, uint32_t data_size)
Callback for device driver library.
Definition: adc_dump.cpp:92
toposens_echo_driver::adcDumpEndCallback
void adcDumpEndCallback(uint16_t sender_id)
Callback for device driver library.
Definition: adc_dump.cpp:94
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
toposens_echo_driver::EchoOneDriver::ts_scan_publisher_
ros::Publisher ts_scan_publisher_
Definition: echo_driver.h:45
toposens_echo_driver::RosParameters::com_interface
std::string com_interface
Definition: ros_utils.h:25
SetParameterTransducerVolume
bool SetParameterTransducerVolume(uint8_t Volume_u8)
Blocking Request to set the Transducer Volume for current target sensor.
Definition: sensor_lib.c:2631
toposens_echo_driver::RosParameters::can_device
std::string can_device
Definition: ros_utils.h:25
toposens_echo_driver::RosParameters::transducer_num_pulses_str
const std::string transducer_num_pulses_str
Definition: ros_utils.h:31
toposens_echo_driver::ConfigureSensorLogMessages
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.
Definition: lib_utils.cpp:202
SetParameterTransducerNumOfPulses
bool SetParameterTransducerNumOfPulses(uint8_t NumOfPulses_u8)
Blocking Request to set the Number of Transducer Pulses for current target sensor.
Definition: sensor_lib.c:2645
toposens_echo_driver::DeinitUARTInterface
void DeinitUARTInterface()
Definition: lib_utils.cpp:20
toposens_echo_driver::LogVersions
void LogVersions()
Read all version information (such as bootloader version, app versionetc.) from sensor and log to ROS...
Definition: lib_utils.cpp:123
GetNumberOfKnownSensors
uint8_t GetNumberOfKnownSensors()
Returns number of known sensors. With GetKnownSensors() users an pointer to an array containing the I...
Definition: sensor_lib.c:799
RegisterADCDumpSessionEndCallback
void RegisterADCDumpSessionEndCallback(void(*Callback)(uint16_t Sender_u16))
Interface function to register a callback function that is called whenever an SessionEnd Payload for ...
Definition: sensor_lib.c:3364
ROS_DEBUG
#define ROS_DEBUG(...)
toposens_echo_driver::RosParameters::uart_device
std::string uart_device
Definition: ros_utils.h:25
toposens_echo_driver::EchoOneDriver::EchoOneDriver
EchoOneDriver(ros::NodeHandle nh, RosParameters parameters)
Definition: echo_driver.cpp:11
ROS_WARN
#define ROS_WARN(...)
toposens_echo_driver::RosParameters::frame_id
std::string frame_id
Definition: ros_utils.h:26
toposens_echo_driver::to_TsScan
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.
Definition: ros_utils.cpp:55
toposens_echo_driver::DeinitCanInterface
void DeinitCanInterface()
Definition: lib_utils.cpp:13
toposens_echo_driver::RosParameters::temperature_str
const std::string temperature_str
Definition: ros_utils.h:32
toposens_echo_driver::RosParameters::transducer_volume
int transducer_volume
Definition: ros_utils.h:28
toposens_echo_driver::getStaticTransformMsg
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.
Definition: ros_utils.cpp:86
toposens_echo_driver::RosParameters::temperature
double temperature
Definition: ros_utils.h:27
toposens_echo_driver
Definition: adc_dump.h:8
SENSOR_MODE_SINGLE_SHOT_TRANSMIT_LISTEN
@ SENSOR_MODE_SINGLE_SHOT_TRANSMIT_LISTEN
Definition: custom_types.h:68
toposens_echo_driver::EchoOneDriver::dynamic_reconfigure_server_
std::unique_ptr< EchoOneDriverConfigServer > dynamic_reconfigure_server_
Definition: echo_driver.h:50
toposens_echo_driver::LogMsgCallback
void LogMsgCallback(uint16_t SenderId_u16, uint8_t *ReceivedPayload_pu8)
Callback handling log messages from sensor.
Definition: lib_utils.cpp:216
toposens_echo_driver::EchoOneDriver::parameters_
RosParameters parameters_
Definition: echo_driver.h:48
SetParameterSystemSensorMode
bool SetParameterSystemSensorMode(SensorMode_t Mode_t)
Blocking Request to set the Sensor Mode for current target sensor.
Definition: sensor_lib.c:2812
adc_dump.h
toposens_echo_driver::EchoOneDriver::~EchoOneDriver
~EchoOneDriver()
Definition: echo_driver.cpp:18
toposens_echo_driver::RosParameters::scans_topic
std::string scans_topic
Definition: ros_utils.h:25
std
toposens_echo_driver::EchoOneDriver::reconfigure
void reconfigure(const EchoOneDriverConfig &config, uint32_t level)
Definition: echo_driver.cpp:131
ROS_ERROR
#define ROS_ERROR(...)
toposens_echo_driver::EchoOneDriver::configureDynamicReconfigureServer
void configureDynamicReconfigureServer()
Definition: echo_driver.cpp:111
toposens_echo_driver::LogSettings
void LogSettings()
Read current configuration from sensor and log to ROS console.
Definition: lib_utils.cpp:54
toposens_echo_driver::InitUARTInterface
void InitUARTInterface(const std::string &uart_device, int data_rate=0010002)
Inits the driver on given uart_device with hard-coded data rate.
Definition: lib_utils.cpp:15
toposens_echo_driver::RosParameters::transducer_num_pulses
int transducer_num_pulses
Definition: ros_utils.h:28
toposens_echo_driver::EchoOneDriver::adc_dump_service_
ros::ServiceServer adc_dump_service_
Definition: echo_driver.h:46
toposens_echo_driver::RosParameters::transducer_volume_str
const std::string transducer_volume_str
Definition: ros_utils.h:30
echo_driver.h
toposens_echo_driver::EchoOneDriver::initialize
void initialize()
Definition: echo_driver.cpp:30
toposens_echo_driver::EchoOneDriver::publishStaticTransforms
void publishStaticTransforms()
Publish static TFs between sensor coordinate frames.
Definition: echo_driver.cpp:88
RegisterADCDumpStartRequestCallback
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 ...
Definition: sensor_lib.c:3415
ROS_INFO
#define ROS_INFO(...)
toposens_echo_driver::RequestSessionData
auto RequestSessionData() -> Sensor_Session_t *
Requesting single shot measurement from first sensor in known sensors array.
Definition: lib_utils.cpp:22
tf::Quaternion
toposens_echo_driver::EchoOneDriver::static_tf_broadcaster_
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
Definition: echo_driver.h:47
SetParameterSignalProcessingTemperature
bool SetParameterSignalProcessingTemperature(float Temperature_f)
Blocking Request to set the Temperature for current target sensor.
Definition: sensor_lib.c:2659
ros::NodeHandle
LOG_LEVEL_INFO
@ LOG_LEVEL_INFO
Definition: custom_types.h:104
ros::Time::now
static Time now()


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