13 #include <sensor_msgs/JointState.h> 14 #include <std_srvs/Empty.h> 16 #include "asr_flir_ptu_driver/Validate.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" 46 void setState(
const asr_flir_ptu_driver::State::ConstPtr& msg);
47 bool updateSettings(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
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);
std::string ptu_pan_frame
bool validatePanTilt(asr_flir_ptu_driver::Validate::Request &req, asr_flir_ptu_driver::Validate::Response &res)
std::string ptu_tilt_frame_rotated
bool updateSpeedControl(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::ServiceServer alive_service
void setState(const asr_flir_ptu_driver::State::ConstPtr &msg)
ros::Publisher joint_pub_old
PTUNode(ros::NodeHandle &n)
PTUNode Constructor for PTUNode class.
std::string service_path_prediction
bool predict(asr_flir_ptu_driver::Predict::Request &req, asr_flir_ptu_driver::Predict::Response &res)
std::string ptu_pan_frame_rotated
bool ok()
ok Method to check if the PTUNode is still working
std::string service_range
ros::Subscriber joint_sub
std::string service_validation
ros::ServiceServer settings_service
ros::ServiceServer validate_service
std::string topic_state_command
bool getRange(asr_flir_ptu_driver::Range::Request &req, asr_flir_ptu_driver::Range::Response &res)
tf::TransformBroadcaster tb_pan
static constexpr double DEG_TO_RAD
asr_flir_ptu_driver::PTUDriver * ptu
ros::ServiceServer path_prediction_service
std::string ptu_topic_state
bool updateSettings(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
std::string service_alive
void spinOnce()
spinOnce Method that is used to spin the PTUNode once, including ros::spinOnce(). Run this in a loop...
ros::NodeHandle node_handle
bool emptyAlive(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
std::string service_settings_update
ros::ServiceServer speedmode_service
std::string service_speed_control_update
std::string ptu_tilt_frame
tf::TransformBroadcaster tb_tilt
ros::ServiceServer range_service