ts_echo_driver_node.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 
6 
7 auto main(int argc, char** argv) -> int
8 {
9  ros::init(argc, argv, "toposens_echo_driver_node");
10 
11  ros::NodeHandle nh;
12  ros::NodeHandle private_nh("~");
13  toposens_echo_driver::RosParameters params(private_nh);
14 
15  if (params.sensor_mode != "single_shot")
16  {
17  ROS_ERROR("Given sensor mode %s not supported yet, aborting launching of node!",
18  params.sensor_mode.c_str());
19  return 0;
20  }
21 
22  ROS_INFO("Launching ECHO ONE Driver node in %s mode!", params.sensor_mode.c_str());
23 
24  toposens_echo_driver::EchoOneDriver driver(nh, params);
25 
26  ros::Rate rate(params.loop_rate_hz);
27  while (ros::ok())
28  {
29  ros::spinOnce();
30 
31  constexpr auto log_interval = double{5};
33  driver.measure();
34  driver.publishStaticTransforms();
35 
36  rate.sleep();
37  }
38 
39  return 0;
40 }
toposens_echo_driver::RosParameters
Definition: ros_utils.h:17
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
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
toposens_echo_driver::RosParameters::loop_rate_hz
double loop_rate_hz
Definition: ros_utils.h:27
lib_utils.h
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
main
auto main(int argc, char **argv) -> int
Definition: ts_echo_driver_node.cpp:7
ros::ok
ROSCPP_DECL bool ok()
toposens_echo_driver::LogKnownSensors
void LogKnownSensors(double log_interval=3.0)
Get currently known sensors from driver and log to ROS console every log_interval seconds.
Definition: lib_utils.cpp:96
toposens_echo_driver::EchoOneDriver
Definition: echo_driver.h:22
ros::Rate::sleep
bool sleep()
ros_utils.h
ROS_ERROR
#define ROS_ERROR(...)
toposens_echo_driver::RosParameters::sensor_mode
std::string sensor_mode
Definition: ros_utils.h:25
ros::Rate
echo_driver.h
toposens_echo_driver::EchoOneDriver::publishStaticTransforms
void publishStaticTransforms()
Publish static TFs between sensor coordinate frames.
Definition: echo_driver.cpp:88
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle


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