Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
PTUNode Class Reference

#include <PTUNode.h>

Public Member Functions

bool ok ()
 ok Method to check if the PTUNode is still working More...
 
 PTUNode (ros::NodeHandle &n)
 PTUNode Constructor for PTUNode class. More...
 
void spinOnce ()
 spinOnce Method that is used to spin the PTUNode once, including ros::spinOnce(). Run this in a loop. More...
 
 ~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::PTUDriverptu
 
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 constexpr double DEG_TO_RAD = M_PI / 180.0
 

Detailed Description

PTUNode class.

Author
Valerij Wittenbeck, Pascal Meissner
Version
See SVN

Definition at line 26 of file PTUNode.h.

Constructor & Destructor Documentation

PTUNode::PTUNode ( ros::NodeHandle n)

PTUNode Constructor for PTUNode class.

Parameters
nnoehandle to use

Definition at line 4 of file PTUNode.cpp.

PTUNode::~PTUNode ( )

Definition at line 65 of file PTUNode.cpp.

Member Function Documentation

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

Returns
True if PTUNode stil works.

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.

Member Data Documentation

ros::ServiceServer PTUNode::alive_service
private

Definition at line 63 of file PTUNode.h.

constexpr double PTUNode::DEG_TO_RAD = M_PI / 180.0
staticprivate

Definition at line 96 of file PTUNode.h.

ros::Publisher PTUNode::joint_pub
private

Definition at line 60 of file PTUNode.h.

ros::Publisher PTUNode::joint_pub_old
private

Definition at line 61 of file PTUNode.h.

ros::Subscriber PTUNode::joint_sub
private

Definition at line 59 of file PTUNode.h.

ros::NodeHandle PTUNode::node_handle
private

Definition at line 57 of file PTUNode.h.

ros::ServiceServer PTUNode::path_prediction_service
private

Definition at line 66 of file PTUNode.h.

asr_flir_ptu_driver::PTUDriver* PTUNode::ptu
private

Definition at line 56 of file PTUNode.h.

std::string PTUNode::ptu_pan_frame
private

Definition at line 78 of file PTUNode.h.

std::string PTUNode::ptu_pan_frame_rotated
private

Definition at line 79 of file PTUNode.h.

std::string PTUNode::ptu_tilt_frame
private

Definition at line 80 of file PTUNode.h.

std::string PTUNode::ptu_tilt_frame_rotated
private

Definition at line 81 of file PTUNode.h.

std::string PTUNode::ptu_topic_state
private

Definition at line 71 of file PTUNode.h.

ros::ServiceServer PTUNode::range_service
private

Definition at line 67 of file PTUNode.h.

int PTUNode::seq_num
private

Definition at line 69 of file PTUNode.h.

std::string PTUNode::service_alive
private

Definition at line 92 of file PTUNode.h.

std::string PTUNode::service_path_prediction
private

Definition at line 93 of file PTUNode.h.

std::string PTUNode::service_range
private

Definition at line 90 of file PTUNode.h.

std::string PTUNode::service_settings_update
private

Definition at line 88 of file PTUNode.h.

std::string PTUNode::service_speed_control_update
private

Definition at line 89 of file PTUNode.h.

std::string PTUNode::service_validation
private

Definition at line 91 of file PTUNode.h.

ros::ServiceServer PTUNode::settings_service
private

Definition at line 64 of file PTUNode.h.

ros::ServiceServer PTUNode::speedmode_service
private

Definition at line 65 of file PTUNode.h.

tf::TransformBroadcaster PTUNode::tb_pan
private

Definition at line 74 of file PTUNode.h.

tf::TransformBroadcaster PTUNode::tb_tilt
private

Definition at line 75 of file PTUNode.h.

std::string PTUNode::topic_state
private

Definition at line 85 of file PTUNode.h.

std::string PTUNode::topic_state_command
private

Definition at line 84 of file PTUNode.h.

ros::ServiceServer PTUNode::validate_service
private

Definition at line 62 of file PTUNode.h.


The documentation for this class was generated from the following files:


asr_flir_ptu_driver
Author(s): Valerij Wittenbeck, Joachim Gehrung, Pascal Meißner, Patrick Schlosser
autogenerated on Mon Dec 2 2019 03:15:17