PTUNode.h
Go to the documentation of this file.
00001 #ifndef PTUNODE_H
00002 #define PTUNODE_H
00003 
00010 #include <math.h>
00011 #include <string.h>
00012 #include "ros/ros.h"
00013 #include <sensor_msgs/JointState.h>
00014 #include <std_srvs/Empty.h>
00015 #include <tf/transform_broadcaster.h>
00016 #include "asr_flir_ptu_driver/Validate.h"
00017 #include "driver/PTUDriver.h"
00018 #include "driver/PTUDriverMock.h"
00019 #include "asr_flir_ptu_driver/State.h"
00020 #include "asr_flir_ptu_driver/Predict.h"
00021 #include "asr_flir_ptu_driver/Range.h"
00022 
00023 //Test porpouse only
00024 #include "PTUFree.h"
00025 
00026 class PTUNode {
00027     public:
00032         PTUNode(ros::NodeHandle& n);
00033         ~PTUNode();
00038         bool ok();
00042         void spinOnce();
00043 
00044 
00045     private:
00046         void setState(const asr_flir_ptu_driver::State::ConstPtr& msg);
00047         bool updateSettings(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00048         bool updateSpeedControl(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00049 
00050         bool setSettings();
00051         bool setSpeedControl();
00052         bool validatePanTilt(asr_flir_ptu_driver::Validate::Request &req, asr_flir_ptu_driver::Validate::Response &res);
00053         bool emptyAlive(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00054         bool predict(asr_flir_ptu_driver::Predict::Request &req, asr_flir_ptu_driver::Predict::Response &res);
00055         bool getRange(asr_flir_ptu_driver::Range::Request &req, asr_flir_ptu_driver::Range::Response &res);
00056         asr_flir_ptu_driver::PTUDriver* ptu;
00057         ros::NodeHandle node_handle;
00058 
00059         ros::Subscriber joint_sub;
00060         ros::Publisher joint_pub;
00061         ros::Publisher joint_pub_old;
00062         ros::ServiceServer validate_service;
00063         ros::ServiceServer alive_service;
00064         ros::ServiceServer settings_service;
00065         ros::ServiceServer speedmode_service;
00066         ros::ServiceServer path_prediction_service;
00067         ros::ServiceServer range_service;
00068         //bool goal_not_reached;
00069         int seq_num;
00070         
00071         std::string ptu_topic_state;
00072 
00073         // broadcasters for PTU coordinate frame
00074         tf::TransformBroadcaster tb_pan;
00075         tf::TransformBroadcaster tb_tilt;
00076 
00077         // descriptors for PTU coordinate frames
00078         std::string ptu_pan_frame;
00079         std::string ptu_pan_frame_rotated;
00080         std::string ptu_tilt_frame;
00081         std::string ptu_tilt_frame_rotated;
00082 
00083         //ROS topics
00084         std::string topic_state_command;
00085         std::string topic_state;
00086 
00087         //ROS services
00088         std::string service_settings_update;
00089         std::string service_speed_control_update;
00090         std::string service_range;
00091         std::string service_validation;
00092         std::string service_alive;
00093         std::string service_path_prediction;
00094 
00095         // used for conversion between radian and degrees
00096         static const double DEG_TO_RAD = M_PI / 180.0;
00097 };
00098 
00099 #endif // PTUNODE_H


asr_flir_ptu_driver
Author(s): Valerij Wittenbeck, Joachim Gehrung, Pascal Meißner, Patrick Schlosser
autogenerated on Thu Jun 6 2019 21:16:45