#include <PTUController.h>
Definition at line 12 of file PTUController.h.
asr_flir_ptu_controller::PTUController::PTUController |
( |
ros::NodeHandle & |
n, |
|
|
std::string |
name |
|
) |
| |
asr_flir_ptu_controller::PTUController::~PTUController |
( |
| ) |
|
void asr_flir_ptu_controller::PTUController::currentStateArrived |
( |
const asr_flir_ptu_driver::State::ConstPtr & |
msg | ) |
|
|
private |
double asr_flir_ptu_controller::PTUController::getCurrentPan |
( |
| ) |
|
double asr_flir_ptu_controller::PTUController::getCurrentTilt |
( |
| ) |
|
std::string asr_flir_ptu_controller::PTUController::getDefaultStateCmdTopicName |
( |
| ) |
|
std::string asr_flir_ptu_controller::PTUController::getDefaultStateTopicName |
( |
| ) |
|
double asr_flir_ptu_controller::PTUController::getMargin |
( |
| ) |
const |
double asr_flir_ptu_controller::PTUController::getMaximumPan |
( |
| ) |
|
double asr_flir_ptu_controller::PTUController::getMaximumTilt |
( |
| ) |
|
int asr_flir_ptu_controller::PTUController::getMaxSteps |
( |
| ) |
|
double asr_flir_ptu_controller::PTUController::getMinimumPan |
( |
| ) |
|
double asr_flir_ptu_controller::PTUController::getMinimumTilt |
( |
| ) |
|
static double asr_flir_ptu_controller::PTUController::getRadianToDegree |
( |
| ) |
|
|
inlinestatic |
double asr_flir_ptu_controller::PTUController::getTimeToWait |
( |
| ) |
|
double asr_flir_ptu_controller::PTUController::getToleranceValue |
( |
| ) |
|
void asr_flir_ptu_controller::PTUController::goalCB |
( |
| ) |
|
|
private |
void asr_flir_ptu_controller::PTUController::preemptCB |
( |
| ) |
|
|
private |
void asr_flir_ptu_controller::PTUController::setMargin |
( |
double |
value | ) |
|
void asr_flir_ptu_controller::PTUController::setSettings |
( |
| ) |
|
|
private |
bool asr_flir_ptu_controller::PTUController::validate |
( |
double |
pan, |
|
|
double |
tilt |
|
) |
| |
|
private |
std::string asr_flir_ptu_controller::PTUController::alive_service |
|
private |
std::string asr_flir_ptu_controller::PTUController::commandTopicName |
|
private |
int asr_flir_ptu_controller::PTUController::count |
|
private |
double asr_flir_ptu_controller::PTUController::current_pan |
|
private |
double asr_flir_ptu_controller::PTUController::current_tilt |
|
private |
double asr_flir_ptu_controller::PTUController::desired_pan |
|
private |
double asr_flir_ptu_controller::PTUController::desired_tilt |
|
private |
std::vector< std::map< std::string, double> > asr_flir_ptu_controller::PTUController::forbiddenAreas |
|
private |
ros::Time asr_flir_ptu_controller::PTUController::lastStateTime |
|
private |
double asr_flir_ptu_controller::PTUController::margin |
|
private |
double asr_flir_ptu_controller::PTUController::max_pan |
|
private |
double asr_flir_ptu_controller::PTUController::max_tilt |
|
private |
int asr_flir_ptu_controller::PTUController::maxSteps |
|
private |
double asr_flir_ptu_controller::PTUController::min_pan |
|
private |
double asr_flir_ptu_controller::PTUController::min_tilt |
|
private |
const double asr_flir_ptu_controller::PTUController::RAD_TO_DEG = 180.0 / M_PI |
|
staticprivate |
int asr_flir_ptu_controller::PTUController::seq_num |
|
private |
asr_flir_ptu_controller::PTUMovementFeedback asr_flir_ptu_controller::PTUController::simpleActionServerFeedback |
|
private |
asr_flir_ptu_controller::PTUMovementResult asr_flir_ptu_controller::PTUController::simpleActionServerResult |
|
private |
double asr_flir_ptu_controller::PTUController::startDistance |
|
private |
sensor_msgs::JointState asr_flir_ptu_controller::PTUController::stateCommandMessage |
|
private |
ros::Publisher asr_flir_ptu_controller::PTUController::stateCommandPublisher |
|
private |
sensor_msgs::JointState asr_flir_ptu_controller::PTUController::target_joint |
|
private |
double asr_flir_ptu_controller::PTUController::timeToWait |
|
private |
double asr_flir_ptu_controller::PTUController::tolerance |
|
private |
std::string asr_flir_ptu_controller::PTUController::topicName |
|
private |
std::string asr_flir_ptu_controller::PTUController::validation_service |
|
private |
The documentation for this class was generated from the following files: