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

Public Member Functions

 SummitXLPad ()
 
void Update ()
 

Private Member Functions

void padCallback (const sensor_msgs::Joy::ConstPtr &joy)
 
int setBumperOverride (bool value)
 
int setManualRelease (bool value)
 

Private Attributes

double a_scale_
 
int angular_
 
bool bEnable
 Flag to enable/disable the communication with the publishers topics. More...
 
bool bOutput1
 
bool bOutput2
 
bool bRegisteredButtonEvent [DEFAULT_NUM_OF_BUTTONS]
 Pointer to a vector for controlling the event when pushing the buttons. More...
 
bool bRegisteredDirectionalArrows [4]
 Pointer to a vector for controlling the event when pushing directional arrows (UNDER AXES ON PX4!) More...
 
int bumper_override_button_
 
int bumper_override_false_number_
 
int bumper_override_true_number_
 
int button_home_
 button to start the homing service More...
 
int button_kinematic_mode_
 button to change kinematic mode More...
 
int button_output_1_
 
int button_output_2_
 
std::string cmd_home_
 Name of the service to do the homing. More...
 
std::string cmd_service_io_
 Name of the service where it will be modifying the digital outputs. More...
 
std::string cmd_set_mode_
 Name of the service to change the mode. More...
 
std::string cmd_topic_ptz_
 Name of the topic where it will be publishing the pant-tilt values. More...
 
std::string cmd_topic_vel_
 Name of the topic where it will be publishing the velocity. More...
 
double current_vel
 
int dead_man_button_
 Number of the DEADMAN button. More...
 
ros::ServiceClient doHome
 Service to start homing. More...
 
std::string joystick_dead_zone_
 Add a dead zone to the joystick that controls scissor and robot rotation (only useful for xWam) More...
 
int kinematic_mode_
 kinematic mode More...
 
double l_scale_
 
double l_scale_z_
 
bool last_command_
 Flag to track the first reading without the deadman's button pressed. More...
 
int linear_x_
 
int linear_y_
 
int linear_z_
 
int manual_release_false_number_
 
int manual_release_true_number_
 
double max_freq_command
 Diagnostics max freq. More...
 
double max_freq_joy
 
double min_freq_command
 Diagnostics min freq. More...
 
double min_freq_joy
 
ros::NodeHandle nh_
 
int num_of_buttons_
 Number of buttons of the joystick. More...
 
int output_1_
 
int output_2_
 
ros::Subscriber pad_sub_
 It will be suscribed to the joystick. More...
 
std::string pad_type_
 Pad type. More...
 
double pan_increment_
 Client of the sound play service. More...
 
ros::NodeHandle pnh_
 
bool ptz_control_by_axes_
 Flag to enable the ptz control via axes. More...
 
int ptz_pan_left_
 
int ptz_pan_right_
 
ros::Publisher ptz_pub_
 
int ptz_tilt_down_
 
int ptz_tilt_up_
 buttons to the pan-tilt-zoom camera More...
 
int ptz_zoom_tele_
 
int ptz_zoom_wide_
 
diagnostic_updater::HeaderlessTopicDiagnosticpub_command_freq
 Diagnostic to control the frequency of the published command velocity topic. More...
 
ros::ServiceClient set_bumper_override_client_
 
ros::ServiceClient set_digital_outputs_client_
 Service to modify the digital outputs. More...
 
ros::ServiceClient set_manual_release_client_
 Service to safety module. More...
 
ros::ServiceClient setKinematicMode
 Service to modify the kinematic mode. More...
 
int speed_down_button_
 
int speed_up_button_
 Number of the button for increase or decrease the speed max of the joystick. More...
 
diagnostic_updater::HeaderlessTopicDiagnosticsus_joy_freq
 Diagnostic to control the reception frequency of the subscribed joy topic. More...
 
double tilt_increment_
 
diagnostic_updater::Updater updater_pad
 General status diagnostic updater. More...
 
ros::Publisher vel_pub_
 It will publish into command velocity (for the robot) and the ptz_state (for the pantilt) More...
 
int zoom_increment_
 Zoom increment (steps) More...
 

Detailed Description

Definition at line 75 of file summit_xl_pad.cpp.

Constructor & Destructor Documentation

SummitXLPad::SummitXLPad ( )

Definition at line 167 of file summit_xl_pad.cpp.

Member Function Documentation

void SummitXLPad::padCallback ( const sensor_msgs::Joy::ConstPtr &  joy)
private

Definition at line 299 of file summit_xl_pad.cpp.

int SummitXLPad::setBumperOverride ( bool  value)
private

Definition at line 682 of file summit_xl_pad.cpp.

int SummitXLPad::setManualRelease ( bool  value)
private

Definition at line 673 of file summit_xl_pad.cpp.

void SummitXLPad::Update ( )

Definition at line 293 of file summit_xl_pad.cpp.

Member Data Documentation

double SummitXLPad::a_scale_
private

Definition at line 90 of file summit_xl_pad.cpp.

int SummitXLPad::angular_
private

Definition at line 89 of file summit_xl_pad.cpp.

bool SummitXLPad::bEnable
private

Flag to enable/disable the communication with the publishers topics.

Definition at line 151 of file summit_xl_pad.cpp.

bool SummitXLPad::bOutput1
private

Definition at line 110 of file summit_xl_pad.cpp.

bool SummitXLPad::bOutput2
private

Definition at line 110 of file summit_xl_pad.cpp.

bool SummitXLPad::bRegisteredButtonEvent[DEFAULT_NUM_OF_BUTTONS]
private

Pointer to a vector for controlling the event when pushing the buttons.

Definition at line 135 of file summit_xl_pad.cpp.

bool SummitXLPad::bRegisteredDirectionalArrows[4]
private

Pointer to a vector for controlling the event when pushing directional arrows (UNDER AXES ON PX4!)

Definition at line 137 of file summit_xl_pad.cpp.

int SummitXLPad::bumper_override_button_
private

Definition at line 105 of file summit_xl_pad.cpp.

int SummitXLPad::bumper_override_false_number_
private

Definition at line 88 of file summit_xl_pad.cpp.

int SummitXLPad::bumper_override_true_number_
private

Definition at line 88 of file summit_xl_pad.cpp.

int SummitXLPad::button_home_
private

button to start the homing service

Definition at line 120 of file summit_xl_pad.cpp.

int SummitXLPad::button_kinematic_mode_
private

button to change kinematic mode

Definition at line 112 of file summit_xl_pad.cpp.

int SummitXLPad::button_output_1_
private

Definition at line 108 of file summit_xl_pad.cpp.

int SummitXLPad::button_output_2_
private

Definition at line 108 of file summit_xl_pad.cpp.

std::string SummitXLPad::cmd_home_
private

Name of the service to do the homing.

Definition at line 124 of file summit_xl_pad.cpp.

std::string SummitXLPad::cmd_service_io_
private

Name of the service where it will be modifying the digital outputs.

Definition at line 98 of file summit_xl_pad.cpp.

std::string SummitXLPad::cmd_set_mode_
private

Name of the service to change the mode.

Definition at line 118 of file summit_xl_pad.cpp.

std::string SummitXLPad::cmd_topic_ptz_
private

Name of the topic where it will be publishing the pant-tilt values.

Definition at line 100 of file summit_xl_pad.cpp.

std::string SummitXLPad::cmd_topic_vel_
private

Name of the topic where it will be publishing the velocity.

Definition at line 96 of file summit_xl_pad.cpp.

double SummitXLPad::current_vel
private

Definition at line 101 of file summit_xl_pad.cpp.

int SummitXLPad::dead_man_button_
private

Number of the DEADMAN button.

Definition at line 105 of file summit_xl_pad.cpp.

ros::ServiceClient SummitXLPad::doHome
private

Service to start homing.

Definition at line 122 of file summit_xl_pad.cpp.

std::string SummitXLPad::joystick_dead_zone_
private

Add a dead zone to the joystick that controls scissor and robot rotation (only useful for xWam)

Definition at line 161 of file summit_xl_pad.cpp.

int SummitXLPad::kinematic_mode_
private

kinematic mode

Definition at line 114 of file summit_xl_pad.cpp.

double SummitXLPad::l_scale_
private

Definition at line 90 of file summit_xl_pad.cpp.

double SummitXLPad::l_scale_z_
private

Definition at line 90 of file summit_xl_pad.cpp.

bool SummitXLPad::last_command_
private

Flag to track the first reading without the deadman's button pressed.

Definition at line 153 of file summit_xl_pad.cpp.

int SummitXLPad::linear_x_
private

Definition at line 89 of file summit_xl_pad.cpp.

int SummitXLPad::linear_y_
private

Definition at line 89 of file summit_xl_pad.cpp.

int SummitXLPad::linear_z_
private

Definition at line 89 of file summit_xl_pad.cpp.

int SummitXLPad::manual_release_false_number_
private

Definition at line 88 of file summit_xl_pad.cpp.

int SummitXLPad::manual_release_true_number_
private

Definition at line 88 of file summit_xl_pad.cpp.

double SummitXLPad::max_freq_command
private

Diagnostics max freq.

Definition at line 149 of file summit_xl_pad.cpp.

double SummitXLPad::max_freq_joy
private

Definition at line 149 of file summit_xl_pad.cpp.

double SummitXLPad::min_freq_command
private

Diagnostics min freq.

Definition at line 147 of file summit_xl_pad.cpp.

double SummitXLPad::min_freq_joy
private

Definition at line 147 of file summit_xl_pad.cpp.

ros::NodeHandle SummitXLPad::nh_
private

Definition at line 85 of file summit_xl_pad.cpp.

int SummitXLPad::num_of_buttons_
private

Number of buttons of the joystick.

Definition at line 133 of file summit_xl_pad.cpp.

int SummitXLPad::output_1_
private

Definition at line 109 of file summit_xl_pad.cpp.

int SummitXLPad::output_2_
private

Definition at line 109 of file summit_xl_pad.cpp.

ros::Subscriber SummitXLPad::pad_sub_
private

It will be suscribed to the joystick.

Definition at line 94 of file summit_xl_pad.cpp.

std::string SummitXLPad::pad_type_
private

Pad type.

Definition at line 103 of file summit_xl_pad.cpp.

double SummitXLPad::pan_increment_
private

Client of the sound play service.

Pan & tilt increment (degrees)

Definition at line 157 of file summit_xl_pad.cpp.

ros::NodeHandle SummitXLPad::pnh_
private

Definition at line 86 of file summit_xl_pad.cpp.

bool SummitXLPad::ptz_control_by_axes_
private

Flag to enable the ptz control via axes.

Definition at line 163 of file summit_xl_pad.cpp.

int SummitXLPad::ptz_pan_left_
private

Definition at line 126 of file summit_xl_pad.cpp.

int SummitXLPad::ptz_pan_right_
private

Definition at line 126 of file summit_xl_pad.cpp.

ros::Publisher SummitXLPad::ptz_pub_
private

Definition at line 92 of file summit_xl_pad.cpp.

int SummitXLPad::ptz_tilt_down_
private

Definition at line 126 of file summit_xl_pad.cpp.

int SummitXLPad::ptz_tilt_up_
private

buttons to the pan-tilt-zoom camera

Definition at line 126 of file summit_xl_pad.cpp.

int SummitXLPad::ptz_zoom_tele_
private

Definition at line 127 of file summit_xl_pad.cpp.

int SummitXLPad::ptz_zoom_wide_
private

Definition at line 127 of file summit_xl_pad.cpp.

diagnostic_updater::HeaderlessTopicDiagnostic* SummitXLPad::pub_command_freq
private

Diagnostic to control the frequency of the published command velocity topic.

Definition at line 141 of file summit_xl_pad.cpp.

ros::ServiceClient SummitXLPad::set_bumper_override_client_
private

Definition at line 131 of file summit_xl_pad.cpp.

ros::ServiceClient SummitXLPad::set_digital_outputs_client_
private

Service to modify the digital outputs.

Definition at line 129 of file summit_xl_pad.cpp.

ros::ServiceClient SummitXLPad::set_manual_release_client_
private

Service to safety module.

Definition at line 131 of file summit_xl_pad.cpp.

ros::ServiceClient SummitXLPad::setKinematicMode
private

Service to modify the kinematic mode.

Definition at line 116 of file summit_xl_pad.cpp.

int SummitXLPad::speed_down_button_
private

Definition at line 107 of file summit_xl_pad.cpp.

int SummitXLPad::speed_up_button_
private

Number of the button for increase or decrease the speed max of the joystick.

Definition at line 107 of file summit_xl_pad.cpp.

diagnostic_updater::HeaderlessTopicDiagnostic* SummitXLPad::sus_joy_freq
private

Diagnostic to control the reception frequency of the subscribed joy topic.

Definition at line 143 of file summit_xl_pad.cpp.

double SummitXLPad::tilt_increment_
private

Definition at line 157 of file summit_xl_pad.cpp.

diagnostic_updater::Updater SummitXLPad::updater_pad
private

General status diagnostic updater.

Definition at line 145 of file summit_xl_pad.cpp.

ros::Publisher SummitXLPad::vel_pub_
private

It will publish into command velocity (for the robot) and the ptz_state (for the pantilt)

Definition at line 92 of file summit_xl_pad.cpp.

int SummitXLPad::zoom_increment_
private

Zoom increment (steps)

Definition at line 159 of file summit_xl_pad.cpp.


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


summit_xl_pad
Author(s):
autogenerated on Tue Apr 27 2021 03:07:13