Public Member Functions | |
SummitXLPad () | |
void | Update () |
Private Member Functions | |
void | padCallback (const sensor_msgs::Joy::ConstPtr &joy) |
Private Attributes | |
double | a_scale_ |
int | angular_ |
bool | bEnable |
Flag to enable/disable the communication with the publishers topics. | |
bool | bOutput1 |
bool | bOutput2 |
bool | bRegisteredButtonEvent [DEFAULT_NUM_OF_BUTTONS] |
Pointer to a vector for controlling the event when pushing the buttons. | |
bool | bRegisteredDirectionalArrows [4] |
Pointer to a vector for controlling the event when pushing directional arrows (UNDER AXES ON PX4!) | |
int | button_home_ |
button to start the homing service | |
int | button_kinematic_mode_ |
button to change kinematic mode | |
int | button_output_1_ |
int | button_output_2_ |
std::string | cmd_home_ |
Name of the service to do the homing. | |
std::string | cmd_service_io_ |
Name of the service where it will be modifying the digital outputs. | |
std::string | cmd_set_mode_ |
Name of the service to change the mode. | |
std::string | cmd_topic_ptz_ |
Name of the topic where it will be publishing the pant-tilt values. | |
std::string | cmd_topic_vel_ |
Name of the topic where it will be publishing the velocity. | |
double | current_vel |
int | dead_man_button_ |
Number of the DEADMAN button. | |
ros::ServiceClient | doHome |
Service to start homing. | |
std::string | joystick_dead_zone_ |
Add a dead zone to the joystick that controls scissor and robot rotation (only useful for xWam) | |
int | kinematic_mode_ |
kinematic mode | |
double | l_scale_ |
double | l_scale_z_ |
bool | last_command_ |
Flag to track the first reading without the deadman's button pressed. | |
int | linear_x_ |
int | linear_y_ |
int | linear_z_ |
double | max_freq_command |
Diagnostics max freq. | |
double | max_freq_joy |
double | min_freq_command |
Diagnostics min freq. | |
double | min_freq_joy |
ros::NodeHandle | nh_ |
int | num_of_buttons_ |
Number of buttons of the joystick. | |
int | output_1_ |
int | output_2_ |
ros::Subscriber | pad_sub_ |
It will be suscribed to the joystick. | |
std::string | pad_type_ |
Pad type. | |
int | pan_increment_ |
Client of the sound play service. | |
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 | |
int | ptz_zoom_tele_ |
int | ptz_zoom_wide_ |
diagnostic_updater::HeaderlessTopicDiagnostic * | pub_command_freq |
Diagnostic to control the frequency of the published command velocity topic. | |
ros::ServiceClient | set_digital_outputs_client_ |
Service to modify the digital outputs. | |
ros::ServiceClient | setKinematicMode |
Service to modify the kinematic mode. | |
int | speed_down_button_ |
int | speed_up_button_ |
Number of the button for increase or decrease the speed max of the joystick. | |
diagnostic_updater::HeaderlessTopicDiagnostic * | sus_joy_freq |
Diagnostic to control the reception frequency of the subscribed joy topic. | |
int | tilt_increment_ |
diagnostic_updater::Updater | updater_pad |
General status diagnostic updater. | |
ros::Publisher | vel_pub_ |
It will publish into command velocity (for the robot) and the ptz_state (for the pantilt) | |
int | zoom_increment_ |
Zoom increment (steps) |
Definition at line 72 of file summit_xl_pad.cpp.
Definition at line 156 of file summit_xl_pad.cpp.
void SummitXLPad::padCallback | ( | const sensor_msgs::Joy::ConstPtr & | joy | ) | [private] |
Definition at line 275 of file summit_xl_pad.cpp.
void SummitXLPad::Update | ( | ) |
Definition at line 269 of file summit_xl_pad.cpp.
double SummitXLPad::a_scale_ [private] |
Definition at line 83 of file summit_xl_pad.cpp.
int SummitXLPad::angular_ [private] |
Definition at line 82 of file summit_xl_pad.cpp.
bool SummitXLPad::bEnable [private] |
Flag to enable/disable the communication with the publishers topics.
Definition at line 142 of file summit_xl_pad.cpp.
bool SummitXLPad::bOutput1 [private] |
Definition at line 103 of file summit_xl_pad.cpp.
bool SummitXLPad::bOutput2 [private] |
Definition at line 103 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 126 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 128 of file summit_xl_pad.cpp.
int SummitXLPad::button_home_ [private] |
button to start the homing service
Definition at line 113 of file summit_xl_pad.cpp.
int SummitXLPad::button_kinematic_mode_ [private] |
button to change kinematic mode
Definition at line 105 of file summit_xl_pad.cpp.
int SummitXLPad::button_output_1_ [private] |
Definition at line 101 of file summit_xl_pad.cpp.
int SummitXLPad::button_output_2_ [private] |
Definition at line 101 of file summit_xl_pad.cpp.
std::string SummitXLPad::cmd_home_ [private] |
Name of the service to do the homing.
Definition at line 117 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 91 of file summit_xl_pad.cpp.
std::string SummitXLPad::cmd_set_mode_ [private] |
Name of the service to change the mode.
Definition at line 111 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 93 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 89 of file summit_xl_pad.cpp.
double SummitXLPad::current_vel [private] |
Definition at line 94 of file summit_xl_pad.cpp.
int SummitXLPad::dead_man_button_ [private] |
Number of the DEADMAN button.
Definition at line 98 of file summit_xl_pad.cpp.
ros::ServiceClient SummitXLPad::doHome [private] |
Service to start homing.
Definition at line 115 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 152 of file summit_xl_pad.cpp.
int SummitXLPad::kinematic_mode_ [private] |
kinematic mode
Definition at line 107 of file summit_xl_pad.cpp.
double SummitXLPad::l_scale_ [private] |
Definition at line 83 of file summit_xl_pad.cpp.
double SummitXLPad::l_scale_z_ [private] |
Definition at line 83 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 144 of file summit_xl_pad.cpp.
int SummitXLPad::linear_x_ [private] |
Definition at line 82 of file summit_xl_pad.cpp.
int SummitXLPad::linear_y_ [private] |
Definition at line 82 of file summit_xl_pad.cpp.
int SummitXLPad::linear_z_ [private] |
Definition at line 82 of file summit_xl_pad.cpp.
double SummitXLPad::max_freq_command [private] |
Diagnostics max freq.
Definition at line 140 of file summit_xl_pad.cpp.
double SummitXLPad::max_freq_joy [private] |
Definition at line 140 of file summit_xl_pad.cpp.
double SummitXLPad::min_freq_command [private] |
Diagnostics min freq.
Definition at line 138 of file summit_xl_pad.cpp.
double SummitXLPad::min_freq_joy [private] |
Definition at line 138 of file summit_xl_pad.cpp.
ros::NodeHandle SummitXLPad::nh_ [private] |
Definition at line 80 of file summit_xl_pad.cpp.
int SummitXLPad::num_of_buttons_ [private] |
Number of buttons of the joystick.
Definition at line 124 of file summit_xl_pad.cpp.
int SummitXLPad::output_1_ [private] |
Definition at line 102 of file summit_xl_pad.cpp.
int SummitXLPad::output_2_ [private] |
Definition at line 102 of file summit_xl_pad.cpp.
ros::Subscriber SummitXLPad::pad_sub_ [private] |
It will be suscribed to the joystick.
Definition at line 87 of file summit_xl_pad.cpp.
std::string SummitXLPad::pad_type_ [private] |
Pad type.
Definition at line 96 of file summit_xl_pad.cpp.
int SummitXLPad::pan_increment_ [private] |
Client of the sound play service.
Pan & tilt increment (degrees)
Definition at line 148 of file summit_xl_pad.cpp.
int SummitXLPad::ptz_pan_left_ [private] |
Definition at line 119 of file summit_xl_pad.cpp.
int SummitXLPad::ptz_pan_right_ [private] |
Definition at line 119 of file summit_xl_pad.cpp.
ros::Publisher SummitXLPad::ptz_pub_ [private] |
Definition at line 85 of file summit_xl_pad.cpp.
int SummitXLPad::ptz_tilt_down_ [private] |
Definition at line 119 of file summit_xl_pad.cpp.
int SummitXLPad::ptz_tilt_up_ [private] |
buttons to the pan-tilt-zoom camera
Definition at line 119 of file summit_xl_pad.cpp.
int SummitXLPad::ptz_zoom_tele_ [private] |
Definition at line 120 of file summit_xl_pad.cpp.
int SummitXLPad::ptz_zoom_wide_ [private] |
Definition at line 120 of file summit_xl_pad.cpp.
Diagnostic to control the frequency of the published command velocity topic.
Definition at line 132 of file summit_xl_pad.cpp.
Service to modify the digital outputs.
Definition at line 122 of file summit_xl_pad.cpp.
Service to modify the kinematic mode.
Definition at line 109 of file summit_xl_pad.cpp.
int SummitXLPad::speed_down_button_ [private] |
Definition at line 100 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 100 of file summit_xl_pad.cpp.
Diagnostic to control the reception frequency of the subscribed joy topic.
Definition at line 134 of file summit_xl_pad.cpp.
int SummitXLPad::tilt_increment_ [private] |
Definition at line 148 of file summit_xl_pad.cpp.
General status diagnostic updater.
Definition at line 136 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 85 of file summit_xl_pad.cpp.
int SummitXLPad::zoom_increment_ [private] |
Zoom increment (steps)
Definition at line 150 of file summit_xl_pad.cpp.