ros_utils.h
Go to the documentation of this file.
1 #ifndef TOPOSENS_ECHO_DRIVER_ROS_UTILS_H
2 #define TOPOSENS_ECHO_DRIVER_ROS_UTILS_H
3 
4 #include <sstream>
5 #include <string>
6 
7 #include <geometry_msgs/TransformStamped.h>
8 #include <ros/ros.h>
9 #include <tf/tf.h>
10 
11 #include <toposens/sensor_lib.h>
12 
13 #include "toposens_msgs/TsScan.h"
14 
15 namespace toposens_echo_driver
16 {
18 {
19 public:
20  RosParameters() = default;
21  explicit RosParameters(ros::NodeHandle private_nh);
22 
23  [[nodiscard]] auto to_string() const -> std::string;
24 
29 
30  const std::string transducer_volume_str{"transducer_volume"};
31  const std::string transducer_num_pulses_str{"transducer_num_pulses"};
32  const std::string temperature_str{"temperature"};
33 
34 private:
35  void load(ros::NodeHandle private_nh);
36 };
37 
44 auto to_TsScan(const Sensor_Session_t* session_data, const RosParameters& params)
45  -> toposens_msgs::TsScan;
46 
52 auto getStaticTransformMsg(const ros::Time& t, const std::vector<float>& trans,
53  const tf::Quaternion& q, const std::string& from, const std::string& to)
54  -> geometry_msgs::TransformStamped;
55 } // namespace toposens_echo_driver
56 
57 #endif // TOPOSENS_ECHO_DRIVER_ROS_UTILS_H
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
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
const std::string transducer_volume_str
Definition: ros_utils.h:30
This file contains the highlevel interface prototypes to the low-level Protocol.
auto to_string() const -> std::string
Definition: ros_utils.cpp:7
void load(ros::NodeHandle private_nh)
Definition: ros_utils.cpp:28
const std::string temperature_str
Definition: ros_utils.h:32
const std::string transducer_num_pulses_str
Definition: ros_utils.h:31


toposens_echo_driver
Author(s): Tobias Roth , Dennis Maier , Baris Yazici
autogenerated on Mon Feb 28 2022 23:57:42