PTUController.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "ros/ros.h"
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"
11 {
13  {
14  public:
15  PTUController(ros::NodeHandle& n, std::string name);
17  double getMaximumPan();
18  double getMinimumPan();
19 
20  double getMaximumTilt();
21  double getMinimumTilt();
22 
23  double getCurrentPan();
24  double getCurrentTilt();
25 
26  std::string getDefaultStateCmdTopicName();
27  std::string getDefaultStateTopicName();
28  double getTimeToWait();
29  double getToleranceValue();
30  int getMaxSteps();
31  static double getRadianToDegree() {return RAD_TO_DEG;}
32 
33  double getMargin() const;
34  void setMargin(double value);
35 
36  private:
37  void goalCB();
38  void preemptCB();
39  void setSettings();
40  void currentStateArrived(const asr_flir_ptu_driver::State::ConstPtr& msg);
41  bool validate(double pan, double tilt);
42  int count;
43  double startDistance;
44 
45  sensor_msgs::JointState target_joint;
48 
53  sensor_msgs::JointState stateCommandMessage;
54 
55  static const double RAD_TO_DEG;
56 
57  double current_pan;
58  double desired_pan;
59  double max_pan;
60  double min_pan;
61 
62  double current_tilt;
63  double desired_tilt;
64  double max_tilt;
65  double min_tilt;
66  int seq_num;
67 
68  int maxSteps;
69  double timeToWait;
70  double tolerance;
71  double margin;
72  std::vector< std::map< std::string, double> > forbiddenAreas;
73  std::string topicName;
74  std::string commandTopicName;
75  std::string validation_service;
76  std::string alive_service;
78  asr_flir_ptu_controller::PTUMovementFeedback simpleActionServerFeedback;
79  asr_flir_ptu_controller::PTUMovementResult simpleActionServerResult;
80  };
81 }
82 
asr_flir_ptu_controller::PTUMovementResult simpleActionServerResult
Definition: PTUController.h:79
sensor_msgs::JointState stateCommandMessage
Definition: PTUController.h:53
std::vector< std::map< std::string, double > > forbiddenAreas
Definition: PTUController.h:72
asr_flir_ptu_controller::PTUMovementFeedback simpleActionServerFeedback
Definition: PTUController.h:78
sensor_msgs::JointState target_joint
Definition: PTUController.h:45
void currentStateArrived(const asr_flir_ptu_driver::State::ConstPtr &msg)
actionlib::SimpleActionServer< asr_flir_ptu_controller::PTUMovementAction > simpleActionServer
Definition: PTUController.h:77
bool validate(double pan, double tilt)
PTUController(ros::NodeHandle &n, std::string name)


asr_flir_ptu_controller
Author(s): Ralph Schleicher, Patrick Schlosser
autogenerated on Sun Nov 24 2019 03:28:47