ros_parameter_handler.h
Go to the documentation of this file.
1 // Copyright (c) 2019-2020 Pilz GmbH & Co. KG
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU Lesser General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU Lesser General Public License for more details.
12 //
13 // You should have received a copy of the GNU Lesser General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #ifndef PSEN_SCAN_ROS_PARAMETER_HANDLER_H
17 #define PSEN_SCAN_ROS_PARAMETER_HANDLER_H
18 
19 #include <ros/ros.h>
21 
22 namespace psen_scan
23 {
29 {
30 public:
33  template <class T>
34  void getRequiredParamFromParamServer(const std::string& key, T& param);
35  template <class T>
36  bool getOptionalParamFromParamServer(const std::string& key, T& param);
37  std::string getPassword() const;
38  uint32_t getHostIP() const;
39  uint32_t getHostUDPPort() const;
40  std::string getSensorIP() const;
41  std::string getFrameID() const;
42  uint16_t getSkip() const;
45  Degree getXAxisRotation() const;
46 
47 private:
49  std::string password_;
50  uint32_t host_ip_;
51  uint32_t host_udp_port_;
52  std::string sensor_ip_;
53  std::string frame_id_;
54  uint16_t skip_;
59 public:
60  static std::string decryptPassword(const std::string& encrypted_password);
61 };
62 } // namespace psen_scan
63 
64 #endif // PSEN_SCAN_ROS_PARAMETER_HANDLER_H
PSENscanInternalAngle getAngleEnd() const
Getter Method for angle_end_.
bool getOptionalParamFromParamServer(const std::string &key, T &param)
Gets one optional ROS-parameter from parameter server.
bool param(const std::string &param_name, T &param_val, const T &default_val)
Class to model angles in degrees from user&#39;s perspective.
Degree getXAxisRotation() const
Getter Method for x_axis_rotation_.
Class for getting ROS-Parameters from the parameter-server.
PSENscanInternalAngle getAngleStart() const
Getter Method for angle_start_.
static std::string decryptPassword(const std::string &encrypted_password)
Decrypt password.
std::string getSensorIP() const
Getter Method for sensor_ip_.
uint16_t getSkip() const
Getter method for skip_.
void getRequiredParamFromParamServer(const std::string &key, T &param)
Gets one required ROS-parameter from parameter server.
uint32_t getHostUDPPort() const
Getter method for host_udp_port_.
uint32_t getHostIP() const
Getter method for host_ip_.
std::string getPassword() const
Getter method for password_.
std::string getFrameID() const
Getter method for frame_id_.
Class to model angles in PSENscan internal format (tenth of degrees)
RosParameterHandler(const ros::NodeHandle &nh)
Construct a new Ros Parameter Handler:: Ros Parameter Handler object.
void updateAllParamsFromParamServer()
Update all Parameters from ROS Parameter Server.


psen_scan
Author(s):
autogenerated on Mon Feb 28 2022 23:16:20