4 #include <sensor_msgs/JointState.h> 6 #include <asr_flir_ptu_controller/PTUMovementAction.h> 7 #include "asr_flir_ptu_driver/Validate.h" 8 #include <std_srvs/Empty.h> 9 #include "asr_flir_ptu_driver/State.h" 41 bool validate(
double pan,
double tilt);
asr_flir_ptu_controller::PTUMovementResult simpleActionServerResult
double getToleranceValue()
sensor_msgs::JointState stateCommandMessage
std::vector< std::map< std::string, double > > forbiddenAreas
ros::Subscriber stateSubscriber
static double getRadianToDegree()
ros::NodeHandle nodeHandle
std::string validation_service
static const double RAD_TO_DEG
std::string commandTopicName
std::string getDefaultStateTopicName()
asr_flir_ptu_controller::PTUMovementFeedback simpleActionServerFeedback
sensor_msgs::JointState target_joint
void currentStateArrived(const asr_flir_ptu_driver::State::ConstPtr &msg)
std::string getDefaultStateCmdTopicName()
std::string alive_service
ros::ServiceClient validate_client
ros::Publisher stateCommandPublisher
actionlib::SimpleActionServer< asr_flir_ptu_controller::PTUMovementAction > simpleActionServer
bool validate(double pan, double tilt)
PTUController(ros::NodeHandle &n, std::string name)
void setMargin(double value)