ros_utils.cpp
Go to the documentation of this file.
2 
3 #include "toposens_msgs/TsScan.h"
4 
5 namespace toposens_echo_driver
6 {
7 [[nodiscard]] auto RosParameters::to_string() const -> std::string
8 {
9  std::stringstream ss;
10 
11  ss << "com_interface: " << com_interface << std::endl;
12  ss << "can_device: " << can_device << std::endl;
13  ss << "uart_device: " << uart_device << std::endl;
14  ss << "scans_topic: " << scans_topic << std::endl;
15  ss << "sensor_mode: " << sensor_mode << std::endl;
16  ss << "frame_id: " << frame_id << std::endl;
17  ss << "target_frame: " << target_frame << std::endl;
18  ss << "loop_rate_hz: " << std::fixed << std::to_string(loop_rate_hz) << std::endl;
19  ss << "temperature: " << std::to_string(temperature) << std::endl;
20  ss << "transducer_volume: " << std::to_string(transducer_volume) << std::endl;
21  ss << "transducer_num_pulses: " << std::to_string(transducer_num_pulses);
22 
23  return ss.str();
24 }
25 
26 RosParameters::RosParameters(const ros::NodeHandle private_nh) { load(private_nh); }
27 
28 void RosParameters::load(const ros::NodeHandle private_nh)
29 {
30  bool success = true;
31 
32  success &= private_nh.getParam("com_interface", com_interface);
33  success &= private_nh.getParam("can_device", can_device);
34  success &= private_nh.getParam("uart_device", uart_device);
35  success &= private_nh.getParam("scans_topic", scans_topic);
36  success &= private_nh.getParam("sensor_mode", sensor_mode);
37  success &= private_nh.getParam("frame_id", frame_id);
38  success &= private_nh.getParam("target_frame", target_frame);
39  success &= private_nh.getParam("loop_rate", loop_rate_hz);
40  success &= private_nh.getParam("signal_processing/temperature", temperature);
41  success &= private_nh.getParam("transducer/volume", transducer_volume);
42  success &= private_nh.getParam("transducer/num_pulses", transducer_num_pulses);
43 
44  if (success)
45  {
46  ROS_DEBUG("Successfully loaded parameters:\n%s", to_string().c_str());
47  }
48  else
49  {
50  ROS_WARN("One or more parameters could not be loaded properly!\nParameters:\n%s",
51  to_string().c_str());
52  }
53 }
54 
55 auto to_TsScan(const Sensor_Session_t* session_data, const RosParameters& parameters)
56  -> toposens_msgs::TsScan
57 {
58  toposens_msgs::TsScan msg;
59 
60  // Information is sent in mm from sensor, ROS works in m, though
61  constexpr auto scaling_factor = double{1000.0};
62 
63  for (auto i = 0; i < session_data->NumberOf3DPoints; ++i)
64  {
65  toposens_msgs::TsPoint point;
66  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
67  point.location.x = session_data->Point3D_tp[i].Z_i16 / scaling_factor;
68  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
69  point.location.y = -session_data->Point3D_tp[i].X_i16 / scaling_factor;
70  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
71  point.location.z = -session_data->Point3D_tp[i].Y_i16 / scaling_factor;
72  // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-constant-array-index)
73  point.intensity = session_data->Point3D_tp[i].Intensity_u8;
74 
75  msg.points.push_back(point);
76  }
77 
78  msg.noisy = session_data->NoiseLevel_u16;
79 
80  msg.header.stamp = ros::Time::now();
81  msg.header.frame_id = parameters.target_frame;
82 
83  return msg;
84 }
85 
86 auto getStaticTransformMsg(const ros::Time& t, const std::vector<float>& trans,
87  const tf::Quaternion& q, const std::string& from, const std::string& to)
88  -> geometry_msgs::TransformStamped
89 {
90  geometry_msgs::TransformStamped msg;
91 
92  msg.header.stamp = t;
93  msg.header.frame_id = from;
94  msg.child_frame_id = to;
95  msg.transform.translation.x = trans.at(0);
96  msg.transform.translation.y = trans.at(1);
97  msg.transform.translation.z = trans.at(2);
98  msg.transform.rotation.x = q.getX();
99  msg.transform.rotation.y = q.getY();
100  msg.transform.rotation.z = q.getZ();
101  msg.transform.rotation.w = q.getW();
102 
103  return msg;
104 }
105 
106 } // 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
toposens_echo_driver::RosParameters::loop_rate_hz
double loop_rate_hz
Definition: ros_utils.h:27
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
toposens_echo_driver::RosParameters::com_interface
std::string com_interface
Definition: ros_utils.h:25
toposens_echo_driver::RosParameters::can_device
std::string can_device
Definition: ros_utils.h:25
ROS_DEBUG
#define ROS_DEBUG(...)
toposens_echo_driver::RosParameters::uart_device
std::string uart_device
Definition: ros_utils.h:25
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::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
toposens_echo_driver::RosParameters::load
void load(ros::NodeHandle private_nh)
Definition: ros_utils.cpp:28
ros_utils.h
ros::Time
toposens_echo_driver::RosParameters::scans_topic
std::string scans_topic
Definition: ros_utils.h:25
std
toposens_echo_driver::RosParameters::to_string
auto to_string() const -> std::string
Definition: ros_utils.cpp:7
Sensor_Session_t
Definition: sensor_lib.h:61
toposens_echo_driver::RosParameters::sensor_mode
std::string sensor_mode
Definition: ros_utils.h:25
toposens_echo_driver::RosParameters::RosParameters
RosParameters()=default
toposens_echo_driver::RosParameters::transducer_num_pulses
int transducer_num_pulses
Definition: ros_utils.h:28
tf::Quaternion
ros::NodeHandle
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