#include <ros/ros.h>#include <sensor_msgs/Joy.h>#include <geometry_msgs/Twist.h>#include <robotnik_msgs/ptz.h>#include <unistd.h>#include <robotnik_msgs/set_mode.h>#include <rb1_base_pad/enable_disable_pad.h>#include <robotnik_msgs/set_digital_output.h>#include <robotnik_msgs/home.h>#include <diagnostic_updater/diagnostic_updater.h>#include <diagnostic_updater/publisher.h>#include <robotnik_msgs/SetElevator.h>#include <robotnik_msgs/ElevatorAction.h>
Go to the source code of this file.
Macros | |
| #define | DEFAULT_AXIS_ANGULAR 2 |
| #define | DEFAULT_AXIS_LINEAR_X 1 |
| #define | DEFAULT_AXIS_LINEAR_Y 0 |
| #define | DEFAULT_AXIS_LINEAR_Z 3 |
| #define | DEFAULT_NUM_OF_BUTTONS 16 |
| #define | DEFAULT_SCALE_ANGULAR 2.0 |
| #define | DEFAULT_SCALE_LINEAR 1.0 |
| #define | DEFAULT_SCALE_LINEAR_Z 1.0 |
| #define | ITERATIONS_AFTER_DEADMAN 3.0 |
| #define | JOY_ERROR_TIME 1.0 |
Functions | |
| bool | EnableDisablePad (rb1_base_pad::enable_disable_pad::Request &req, rb1_base_pad::enable_disable_pad::Response &res) |
| int | main (int argc, char **argv) |
| void | padCallback (const sensor_msgs::Joy::ConstPtr &joy) |
| void | Update () |
Variables | |
| double | a_scale_ |
| int | angular_ |
| int | axis_elevator_ |
| bool | bOutput1 |
| bool | bOutput2 |
| bool | bRegisteredButtonEvent [DEFAULT_NUM_OF_BUTTONS] |
| Pointer to a vector for controlling the event when pushing the buttons. More... | |
| int | button_home_ |
| button to start the homing service More... | |
| int | button_kinematic_mode_ |
| button to change kinematic mode More... | |
| int | button_lower_elevator_ |
| int | button_output_1_ |
| int | button_output_2_ |
| int | button_raise_elevator_ |
| int | button_stop_elevator_ |
| bool | check_message_timeout_ |
| If it is True, it will check the timeout message. More... | |
| 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 | elevator_service_name_ |
| Name of the service where to actuate the elevator. More... | |
| int | kinematic_mode_ |
| kinematic mode More... | |
| double | l_scale_ |
| double | l_scale_z_ |
| int | linear_x_ |
| int | linear_y_ |
| int | linear_z_ |
| 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_ |
| * | NOTE |
| 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... | |
| int | pan_increment_ |
| Flag to enable/disable the communication with the publishers topics. 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... | |
| diagnostic_updater::HeaderlessTopicDiagnostic * | pub_command_freq |
| Diagnostic to control the frequency of the published command velocity topic. More... | |
| ros::ServiceClient | set_digital_outputs_client_ |
| Enables/disables the pad. More... | |
| ros::ServiceClient | set_elevator_client_ |
| Service to activate the elevator. 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::HeaderlessTopicDiagnostic * | sus_joy_freq |
| Diagnostic to control the reception frequency of the subscribed joy topic. More... | |
| int | 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... | |
| #define DEFAULT_AXIS_ANGULAR 2 |
Definition at line 55 of file rb1_base_pad.cpp.
| #define DEFAULT_AXIS_LINEAR_X 1 |
Definition at line 53 of file rb1_base_pad.cpp.
| #define DEFAULT_AXIS_LINEAR_Y 0 |
Definition at line 54 of file rb1_base_pad.cpp.
| #define DEFAULT_AXIS_LINEAR_Z 3 |
Definition at line 56 of file rb1_base_pad.cpp.
| #define DEFAULT_NUM_OF_BUTTONS 16 |
Definition at line 52 of file rb1_base_pad.cpp.
| #define DEFAULT_SCALE_ANGULAR 2.0 |
Definition at line 58 of file rb1_base_pad.cpp.
| #define DEFAULT_SCALE_LINEAR 1.0 |
Definition at line 57 of file rb1_base_pad.cpp.
| #define DEFAULT_SCALE_LINEAR_Z 1.0 |
Definition at line 59 of file rb1_base_pad.cpp.
| #define ITERATIONS_AFTER_DEADMAN 3.0 |
Definition at line 61 of file rb1_base_pad.cpp.
| #define JOY_ERROR_TIME 1.0 |
Definition at line 63 of file rb1_base_pad.cpp.
|
private |
|
private |
Definition at line 365 of file rb1_base_pad.cpp.
|
private |
Definition at line 268 of file rb1_base_pad.cpp.
| void RB1BasePad::Update | ( | ) |
Definition at line 249 of file rb1_base_pad.cpp.
|
private |
Definition at line 86 of file rb1_base_pad.cpp.
|
private |
Definition at line 85 of file rb1_base_pad.cpp.
|
private |
Definition at line 107 of file rb1_base_pad.cpp.
|
private |
Definition at line 109 of file rb1_base_pad.cpp.
|
private |
Definition at line 109 of file rb1_base_pad.cpp.
|
private |
Pointer to a vector for controlling the event when pushing the buttons.
Definition at line 136 of file rb1_base_pad.cpp.
|
private |
button to start the homing service
Definition at line 119 of file rb1_base_pad.cpp.
|
private |
button to change kinematic mode
Definition at line 111 of file rb1_base_pad.cpp.
|
private |
Definition at line 107 of file rb1_base_pad.cpp.
|
private |
Definition at line 106 of file rb1_base_pad.cpp.
|
private |
Definition at line 106 of file rb1_base_pad.cpp.
|
private |
Definition at line 107 of file rb1_base_pad.cpp.
|
private |
Definition at line 107 of file rb1_base_pad.cpp.
|
private |
If it is True, it will check the timeout message.
Definition at line 100 of file rb1_base_pad.cpp.
|
private |
Name of the service to do the homing.
Definition at line 123 of file rb1_base_pad.cpp.
|
private |
Name of the service where it will be modifying the digital outputs.
Definition at line 94 of file rb1_base_pad.cpp.
|
private |
Name of the service to change the mode.
Definition at line 117 of file rb1_base_pad.cpp.
|
private |
Name of the topic where it will be publishing the pant-tilt values.
Definition at line 98 of file rb1_base_pad.cpp.
|
private |
Name of the topic where it will be publishing the velocity.
Definition at line 92 of file rb1_base_pad.cpp.
|
private |
Definition at line 101 of file rb1_base_pad.cpp.
|
private |
Number of the DEADMAN button.
Definition at line 103 of file rb1_base_pad.cpp.
|
private |
Service to start homing.
Definition at line 121 of file rb1_base_pad.cpp.
|
private |
Name of the service where to actuate the elevator.
Definition at line 96 of file rb1_base_pad.cpp.
|
private |
kinematic mode
Definition at line 113 of file rb1_base_pad.cpp.
|
private |
Definition at line 86 of file rb1_base_pad.cpp.
|
private |
Definition at line 86 of file rb1_base_pad.cpp.
|
private |
Definition at line 85 of file rb1_base_pad.cpp.
|
private |
Definition at line 85 of file rb1_base_pad.cpp.
|
private |
Definition at line 85 of file rb1_base_pad.cpp.
|
private |
Diagnostics max freq.
Definition at line 147 of file rb1_base_pad.cpp.
|
private |
Definition at line 147 of file rb1_base_pad.cpp.
|
private |
Diagnostics min freq.
Definition at line 145 of file rb1_base_pad.cpp.
|
private |
Definition at line 145 of file rb1_base_pad.cpp.
|
private |
Definition at line 83 of file rb1_base_pad.cpp.
| * NOTE |
Definition at line 76 of file rb1_base_pad.cpp.
|
private |
Number of buttons of the joystick.
Definition at line 134 of file rb1_base_pad.cpp.
|
private |
Definition at line 108 of file rb1_base_pad.cpp.
|
private |
Definition at line 108 of file rb1_base_pad.cpp.
|
private |
It will be suscribed to the joystick.
Definition at line 90 of file rb1_base_pad.cpp.
|
private |
Flag to enable/disable the communication with the publishers topics.
Client of the sound play service Pan & tilt increment (degrees)
Definition at line 153 of file rb1_base_pad.cpp.
|
private |
Definition at line 125 of file rb1_base_pad.cpp.
|
private |
Definition at line 125 of file rb1_base_pad.cpp.
|
private |
Definition at line 88 of file rb1_base_pad.cpp.
|
private |
Definition at line 125 of file rb1_base_pad.cpp.
|
private |
buttons to the pan-tilt-zoom camera
Definition at line 125 of file rb1_base_pad.cpp.
|
private |
Diagnostic to control the frequency of the published command velocity topic.
Definition at line 139 of file rb1_base_pad.cpp.
|
private |
Enables/disables the pad.
Service to modify the digital outputs
Definition at line 130 of file rb1_base_pad.cpp.
|
private |
Service to activate the elevator.
Definition at line 132 of file rb1_base_pad.cpp.
|
private |
Service to modify the kinematic mode.
Definition at line 115 of file rb1_base_pad.cpp.
|
private |
Definition at line 105 of file rb1_base_pad.cpp.
|
private |
Number of the button for increase or decrease the speed max of the joystick.
Definition at line 105 of file rb1_base_pad.cpp.
|
private |
Diagnostic to control the reception frequency of the subscribed joy topic.
Definition at line 141 of file rb1_base_pad.cpp.
|
private |
Definition at line 153 of file rb1_base_pad.cpp.
|
private |
General status diagnostic updater.
Definition at line 143 of file rb1_base_pad.cpp.
|
private |
It will publish into command velocity (for the robot) and the ptz_state (for the pantilt)
Definition at line 88 of file rb1_base_pad.cpp.