sensor.h
Go to the documentation of this file.
1 
6 #ifndef SENSOR_H
7 #define SENSOR_H
8 
9 #include <dynamic_reconfigure/server.h>
10 #include <ros/ros.h>
11 #include <boost/thread/recursive_mutex.hpp>
12 
13 #include <toposens_driver/TsDriverConfig.h>
14 #include <toposens_driver/serial.h>
15 #include <toposens_msgs/TsScan.h>
16 
17 namespace toposens_driver
18 {
20 static const char kScansTopic[] = "ts_scans";
22 static const int kQueueSize = 100;
23 
31 class Sensor
32 {
33 public:
40  enum ScanMode
41  {
45  };
46 
51  Sensor(ros::NodeHandle nh, ros::NodeHandle private_nh);
52 
62  Sensor(ros::NodeHandle nh, ros::NodeHandle private_nh, std::string port, std::string frame_id);
63 
64  ~Sensor() {}
65 
69  void setMode(ScanMode scan_mode);
70 
76  bool poll(void);
77 
79  void shutdown(void);
80 
81 private:
84  typedef dynamic_reconfigure::Server<TsDriverConfig> Cfg;
85 
89  void _init(void);
90 
98  void _reconfig(TsDriverConfig &cfg, uint32_t level);
99 
104  void _parse(const std::string &frame);
105 
117  bool _evaluateAck(Command &cmd, const std::string &frame);
118 
135  Command *_parseAck(const std::string &data);
136 
141  void _updateConfig(TsParam param, int value);
142 
147 
150 
157  float _toNum(auto &i);
158 
159  std::string _frame_id;
160  TsDriverConfig _cfg;
161  std::unique_ptr<Cfg> _srv;
162  boost::recursive_mutex mutex;
165  std::unique_ptr<Serial> _serial;
166  std::stringstream _buffer;
168  toposens_msgs::TsScan _scan;
169 };
170 
171 } // namespace toposens_driver
172 
173 #endif
toposens_driver::Sensor::mutex
boost::recursive_mutex mutex
Definition: sensor.h:162
toposens_driver::Sensor::_toNum
float _toNum(auto &i)
Definition: sensor.cpp:446
toposens_driver::Sensor::ScanOnce
@ ScanOnce
Definition: sensor.h:43
ros::Publisher
toposens_driver::Sensor::_cfg
TsDriverConfig _cfg
Definition: sensor.h:160
toposens_driver::Sensor::_buffer
std::stringstream _buffer
Definition: sensor.h:166
toposens_driver::Sensor::_scan
toposens_msgs::TsScan _scan
Definition: sensor.h:168
ros.h
toposens_driver::Sensor::_synchronizeParameterValues
void _synchronizeParameterValues()
Definition: sensor.cpp:409
toposens_driver::Sensor::_srv
std::unique_ptr< Cfg > _srv
Definition: sensor.h:161
toposens_driver::TsParam
TsParam
Definition: command.h:22
toposens_driver::Sensor::_reconfig
void _reconfig(TsDriverConfig &cfg, uint32_t level)
Definition: sensor.cpp:180
toposens_driver
Definition: command.h:12
toposens_driver::Sensor::_evaluateAck
bool _evaluateAck(Command &cmd, const std::string &frame)
Definition: sensor.cpp:349
toposens_driver::kQueueSize
static const int kQueueSize
Definition: sensor.h:22
toposens_driver::Sensor::~Sensor
~Sensor()
Definition: sensor.h:64
toposens_driver::Sensor::Cfg
dynamic_reconfigure::Server< TsDriverConfig > Cfg
Definition: sensor.h:84
toposens_driver::Sensor::ListenOnce
@ ListenOnce
Definition: sensor.h:44
toposens_driver::Sensor::Sensor
Sensor(ros::NodeHandle nh, ros::NodeHandle private_nh)
Definition: sensor.cpp:13
toposens_driver::Sensor::_pub
ros::Publisher _pub
Definition: sensor.h:164
toposens_driver::Sensor::_updateConfig
void _updateConfig(TsParam param, int value)
Definition: sensor.cpp:390
toposens_driver::Sensor::_parse
void _parse(const std::string &frame)
Definition: sensor.cpp:290
toposens_driver::Sensor::_serial
std::unique_ptr< Serial > _serial
Definition: sensor.h:165
toposens_driver::kScansTopic
static const char kScansTopic[]
Definition: sensor.h:20
serial.h
toposens_driver::Command
Generates firmware-compatible commands for tuning performance parameters.
Definition: command.h:60
toposens_driver::Sensor::setMode
void setMode(ScanMode scan_mode)
Definition: sensor.cpp:62
toposens_driver::Sensor::ScanContinuously
@ ScanContinuously
Definition: sensor.h:42
toposens_driver::Sensor::_frame_id
std::string _frame_id
Definition: sensor.h:159
toposens_driver::Sensor
Converts raw sensor data to ROS friendly message structures.
Definition: sensor.h:31
toposens_driver::Sensor::shutdown
void shutdown(void)
Definition: sensor.cpp:126
toposens_driver::Sensor::ScanMode
ScanMode
Definition: sensor.h:40
toposens_driver::Sensor::_init
void _init(void)
Definition: sensor.cpp:141
toposens_driver::Sensor::_parseAck
Command * _parseAck(const std::string &data)
Definition: sensor.cpp:335
toposens_driver::Sensor::poll
bool poll(void)
Definition: sensor.cpp:103
toposens_driver::Sensor::_displayFirmwareVersion
void _displayFirmwareVersion()
Definition: sensor.cpp:70
ros::NodeHandle


toposens_driver
Author(s): Adi Singh, Sebastian Dengler, Christopher Lang, Roua Mokchah, Nancy Seckel, Georgiana Barbut
autogenerated on Wed Mar 2 2022 01:12:30