#include <PTUNode.h>
Public Member Functions | |
| bool | ok () |
| ok Method to check if the PTUNode is still working | |
| PTUNode (ros::NodeHandle &n) | |
| PTUNode Constructor for PTUNode class. | |
| void | spinOnce () |
| spinOnce Method that is used to spin the PTUNode once, including ros::spinOnce(). Run this in a loop. | |
| ~PTUNode () | |
Private Member Functions | |
| bool | emptyAlive (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| bool | getRange (asr_flir_ptu_driver::Range::Request &req, asr_flir_ptu_driver::Range::Response &res) |
| bool | predict (asr_flir_ptu_driver::Predict::Request &req, asr_flir_ptu_driver::Predict::Response &res) |
| bool | setSettings () |
| bool | setSpeedControl () |
| void | setState (const asr_flir_ptu_driver::State::ConstPtr &msg) |
| bool | updateSettings (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
| bool | updateSpeedControl (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
| bool | validatePanTilt (asr_flir_ptu_driver::Validate::Request &req, asr_flir_ptu_driver::Validate::Response &res) |
Private Attributes | |
| ros::ServiceServer | alive_service |
| ros::Publisher | joint_pub |
| ros::Publisher | joint_pub_old |
| ros::Subscriber | joint_sub |
| ros::NodeHandle | node_handle |
| ros::ServiceServer | path_prediction_service |
| asr_flir_ptu_driver::PTUDriver * | ptu |
| std::string | ptu_pan_frame |
| std::string | ptu_pan_frame_rotated |
| std::string | ptu_tilt_frame |
| std::string | ptu_tilt_frame_rotated |
| std::string | ptu_topic_state |
| ros::ServiceServer | range_service |
| int | seq_num |
| std::string | service_alive |
| std::string | service_path_prediction |
| std::string | service_range |
| std::string | service_settings_update |
| std::string | service_speed_control_update |
| std::string | service_validation |
| ros::ServiceServer | settings_service |
| ros::ServiceServer | speedmode_service |
| tf::TransformBroadcaster | tb_pan |
| tf::TransformBroadcaster | tb_tilt |
| std::string | topic_state |
| std::string | topic_state_command |
| ros::ServiceServer | validate_service |
Static Private Attributes | |
| static const double | DEG_TO_RAD = M_PI / 180.0 |
| PTUNode::PTUNode | ( | ros::NodeHandle & | n | ) |
PTUNode Constructor for PTUNode class.
| n | noehandle to use |
Definition at line 4 of file PTUNode.cpp.
Definition at line 65 of file PTUNode.cpp.
| bool PTUNode::emptyAlive | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [private] |
Definition at line 129 of file PTUNode.cpp.
| bool PTUNode::getRange | ( | asr_flir_ptu_driver::Range::Request & | req, |
| asr_flir_ptu_driver::Range::Response & | res | ||
| ) | [private] |
Definition at line 140 of file PTUNode.cpp.
| bool PTUNode::ok | ( | ) |
ok Method to check if the PTUNode is still working
Definition at line 309 of file PTUNode.cpp.
| bool PTUNode::predict | ( | asr_flir_ptu_driver::Predict::Request & | req, |
| asr_flir_ptu_driver::Predict::Response & | res | ||
| ) | [private] |
Definition at line 121 of file PTUNode.cpp.
| bool PTUNode::setSettings | ( | ) | [private] |
Definition at line 159 of file PTUNode.cpp.
| bool PTUNode::setSpeedControl | ( | ) | [private] |
Definition at line 288 of file PTUNode.cpp.
| void PTUNode::setState | ( | const asr_flir_ptu_driver::State::ConstPtr & | msg | ) | [private] |
Definition at line 72 of file PTUNode.cpp.
| void PTUNode::spinOnce | ( | ) |
spinOnce Method that is used to spin the PTUNode once, including ros::spinOnce(). Run this in a loop.
Definition at line 313 of file PTUNode.cpp.
| bool PTUNode::updateSettings | ( | std_srvs::Empty::Request & | , |
| std_srvs::Empty::Response & | |||
| ) | [private] |
Definition at line 136 of file PTUNode.cpp.
| bool PTUNode::updateSpeedControl | ( | std_srvs::Empty::Request & | , |
| std_srvs::Empty::Response & | |||
| ) | [private] |
Definition at line 284 of file PTUNode.cpp.
| bool PTUNode::validatePanTilt | ( | asr_flir_ptu_driver::Validate::Request & | req, |
| asr_flir_ptu_driver::Validate::Response & | res | ||
| ) | [private] |
Definition at line 96 of file PTUNode.cpp.
ros::ServiceServer PTUNode::alive_service [private] |
const double PTUNode::DEG_TO_RAD = M_PI / 180.0 [static, private] |
ros::Publisher PTUNode::joint_pub [private] |
ros::Publisher PTUNode::joint_pub_old [private] |
ros::Subscriber PTUNode::joint_sub [private] |
ros::NodeHandle PTUNode::node_handle [private] |
asr_flir_ptu_driver::PTUDriver* PTUNode::ptu [private] |
std::string PTUNode::ptu_pan_frame [private] |
std::string PTUNode::ptu_pan_frame_rotated [private] |
std::string PTUNode::ptu_tilt_frame [private] |
std::string PTUNode::ptu_tilt_frame_rotated [private] |
std::string PTUNode::ptu_topic_state [private] |
ros::ServiceServer PTUNode::range_service [private] |
int PTUNode::seq_num [private] |
std::string PTUNode::service_alive [private] |
std::string PTUNode::service_path_prediction [private] |
std::string PTUNode::service_range [private] |
std::string PTUNode::service_settings_update [private] |
std::string PTUNode::service_speed_control_update [private] |
std::string PTUNode::service_validation [private] |
ros::ServiceServer PTUNode::settings_service [private] |
ros::ServiceServer PTUNode::speedmode_service [private] |
tf::TransformBroadcaster PTUNode::tb_pan [private] |
tf::TransformBroadcaster PTUNode::tb_tilt [private] |
std::string PTUNode::topic_state [private] |
std::string PTUNode::topic_state_command [private] |
ros::ServiceServer PTUNode::validate_service [private] |