PTUNode.h
Go to the documentation of this file.
1 #ifndef PTUNODE_H
2 #define PTUNODE_H
3 
10 #include <math.h>
11 #include <string.h>
12 #include "ros/ros.h"
13 #include <sensor_msgs/JointState.h>
14 #include <std_srvs/Empty.h>
16 #include "asr_flir_ptu_driver/Validate.h"
17 #include "driver/PTUDriver.h"
18 #include "driver/PTUDriverMock.h"
19 #include "asr_flir_ptu_driver/State.h"
20 #include "asr_flir_ptu_driver/Predict.h"
21 #include "asr_flir_ptu_driver/Range.h"
22 
23 //Test porpouse only
24 #include "PTUFree.h"
25 
26 class PTUNode {
27  public:
33  ~PTUNode();
38  bool ok();
42  void spinOnce();
43 
44 
45  private:
46  void setState(const asr_flir_ptu_driver::State::ConstPtr& msg);
47  bool updateSettings(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
48  bool updateSpeedControl(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
49 
50  bool setSettings();
51  bool setSpeedControl();
52  bool validatePanTilt(asr_flir_ptu_driver::Validate::Request &req, asr_flir_ptu_driver::Validate::Response &res);
53  bool emptyAlive(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
54  bool predict(asr_flir_ptu_driver::Predict::Request &req, asr_flir_ptu_driver::Predict::Response &res);
55  bool getRange(asr_flir_ptu_driver::Range::Request &req, asr_flir_ptu_driver::Range::Response &res);
58 
68  //bool goal_not_reached;
69  int seq_num;
70 
71  std::string ptu_topic_state;
72 
73  // broadcasters for PTU coordinate frame
76 
77  // descriptors for PTU coordinate frames
78  std::string ptu_pan_frame;
79  std::string ptu_pan_frame_rotated;
80  std::string ptu_tilt_frame;
82 
83  //ROS topics
84  std::string topic_state_command;
85  std::string topic_state;
86 
87  //ROS services
90  std::string service_range;
91  std::string service_validation;
92  std::string service_alive;
94 
95  // used for conversion between radian and degrees
96  static constexpr double DEG_TO_RAD = M_PI / 180.0;
97 };
98 
99 #endif // PTUNODE_H
int seq_num
Definition: PTUNode.h:69
std::string ptu_pan_frame
Definition: PTUNode.h:78
bool validatePanTilt(asr_flir_ptu_driver::Validate::Request &req, asr_flir_ptu_driver::Validate::Response &res)
Definition: PTUNode.cpp:96
std::string ptu_tilt_frame_rotated
Definition: PTUNode.h:81
std::string topic_state
Definition: PTUNode.h:85
bool updateSpeedControl(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: PTUNode.cpp:284
~PTUNode()
Definition: PTUNode.cpp:65
ros::ServiceServer alive_service
Definition: PTUNode.h:63
bool setSettings()
Definition: PTUNode.cpp:159
ros::Publisher joint_pub
Definition: PTUNode.h:60
void setState(const asr_flir_ptu_driver::State::ConstPtr &msg)
Definition: PTUNode.cpp:72
ros::Publisher joint_pub_old
Definition: PTUNode.h:61
PTUNode(ros::NodeHandle &n)
PTUNode Constructor for PTUNode class.
Definition: PTUNode.cpp:4
std::string service_path_prediction
Definition: PTUNode.h:93
bool predict(asr_flir_ptu_driver::Predict::Request &req, asr_flir_ptu_driver::Predict::Response &res)
Definition: PTUNode.cpp:121
std::string ptu_pan_frame_rotated
Definition: PTUNode.h:79
bool ok()
ok Method to check if the PTUNode is still working
Definition: PTUNode.cpp:309
std::string service_range
Definition: PTUNode.h:90
ros::Subscriber joint_sub
Definition: PTUNode.h:59
std::string service_validation
Definition: PTUNode.h:91
ros::ServiceServer settings_service
Definition: PTUNode.h:64
ros::ServiceServer validate_service
Definition: PTUNode.h:62
std::string topic_state_command
Definition: PTUNode.h:84
bool getRange(asr_flir_ptu_driver::Range::Request &req, asr_flir_ptu_driver::Range::Response &res)
Definition: PTUNode.cpp:140
tf::TransformBroadcaster tb_pan
Definition: PTUNode.h:74
static constexpr double DEG_TO_RAD
Definition: PTUNode.h:96
asr_flir_ptu_driver::PTUDriver * ptu
Definition: PTUNode.h:56
ros::ServiceServer path_prediction_service
Definition: PTUNode.h:66
std::string ptu_topic_state
Definition: PTUNode.h:71
bool updateSettings(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: PTUNode.cpp:136
std::string service_alive
Definition: PTUNode.h:92
void spinOnce()
spinOnce Method that is used to spin the PTUNode once, including ros::spinOnce(). Run this in a loop...
Definition: PTUNode.cpp:313
ros::NodeHandle node_handle
Definition: PTUNode.h:57
bool emptyAlive(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: PTUNode.cpp:129
std::string service_settings_update
Definition: PTUNode.h:88
ros::ServiceServer speedmode_service
Definition: PTUNode.h:65
std::string service_speed_control_update
Definition: PTUNode.h:89
bool setSpeedControl()
Definition: PTUNode.cpp:288
std::string ptu_tilt_frame
Definition: PTUNode.h:80
tf::TransformBroadcaster tb_tilt
Definition: PTUNode.h:75
ros::ServiceServer range_service
Definition: PTUNode.h:67


asr_flir_ptu_driver
Author(s): Valerij Wittenbeck, Joachim Gehrung, Pascal Meißner, Patrick Schlosser
autogenerated on Mon Dec 2 2019 03:15:17