Public Member Functions | |
RB1BasePad () | |
void | Update () |
Private Member Functions | |
bool | EnableDisablePad (rb1_base_pad::enable_disable_pad::Request &req, rb1_base_pad::enable_disable_pad::Response &res) |
void | padCallback (const sensor_msgs::Joy::ConstPtr &joy) |
Private Attributes | |
double | a_scale_ |
int | angular_ |
bool | bOutput1 |
bool | bOutput2 |
bool | bRegisteredButtonEvent [DEFAULT_NUM_OF_BUTTONS] |
Pointer to a vector for controlling the event when pushing the buttons. | |
int | button_home_ |
button to start the homing service | |
int | button_kinematic_mode_ |
button to change kinematic mode | |
int | button_lower_elevator_ |
int | button_output_1_ |
int | button_output_2_ |
int | button_raise_elevator_ |
int | button_stop_elevator_ |
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 | elevator_service_name_ |
Name of the service where to actuate the elevator. | |
int | kinematic_mode_ |
kinematic mode | |
double | l_scale_ |
double | l_scale_z_ |
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. | |
int | pan_increment_ |
Flag to enable/disable the communication with the publishers topics. | |
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 | |
diagnostic_updater::HeaderlessTopicDiagnostic * | pub_command_freq |
Diagnostic to control the frequency of the published command velocity topic. | |
ros::ServiceClient | set_digital_outputs_client_ |
Enables/disables the pad. | |
ros::ServiceClient | set_elevator_client_ |
Service to activate the elevator. | |
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) |
Definition at line 73 of file rb1_base_pad.cpp.
Definition at line 155 of file rb1_base_pad.cpp.
bool RB1BasePad::EnableDisablePad | ( | rb1_base_pad::enable_disable_pad::Request & | req, |
rb1_base_pad::enable_disable_pad::Response & | res | ||
) | [private] |
void RB1BasePad::padCallback | ( | const sensor_msgs::Joy::ConstPtr & | joy | ) | [private] |
Definition at line 265 of file rb1_base_pad.cpp.
void RB1BasePad::Update | ( | ) |
Definition at line 246 of file rb1_base_pad.cpp.
double RB1BasePad::a_scale_ [private] |
Definition at line 86 of file rb1_base_pad.cpp.
int RB1BasePad::angular_ [private] |
Definition at line 85 of file rb1_base_pad.cpp.
bool RB1BasePad::bOutput1 [private] |
Definition at line 107 of file rb1_base_pad.cpp.
bool RB1BasePad::bOutput2 [private] |
Definition at line 107 of file rb1_base_pad.cpp.
bool RB1BasePad::bRegisteredButtonEvent[DEFAULT_NUM_OF_BUTTONS] [private] |
Pointer to a vector for controlling the event when pushing the buttons.
Definition at line 134 of file rb1_base_pad.cpp.
int RB1BasePad::button_home_ [private] |
button to start the homing service
Definition at line 117 of file rb1_base_pad.cpp.
int RB1BasePad::button_kinematic_mode_ [private] |
button to change kinematic mode
Definition at line 109 of file rb1_base_pad.cpp.
int RB1BasePad::button_lower_elevator_ [private] |
Definition at line 105 of file rb1_base_pad.cpp.
int RB1BasePad::button_output_1_ [private] |
Definition at line 104 of file rb1_base_pad.cpp.
int RB1BasePad::button_output_2_ [private] |
Definition at line 104 of file rb1_base_pad.cpp.
int RB1BasePad::button_raise_elevator_ [private] |
Definition at line 105 of file rb1_base_pad.cpp.
int RB1BasePad::button_stop_elevator_ [private] |
Definition at line 105 of file rb1_base_pad.cpp.
std::string RB1BasePad::cmd_home_ [private] |
Name of the service to do the homing.
Definition at line 121 of file rb1_base_pad.cpp.
std::string RB1BasePad::cmd_service_io_ [private] |
Name of the service where it will be modifying the digital outputs.
Definition at line 94 of file rb1_base_pad.cpp.
std::string RB1BasePad::cmd_set_mode_ [private] |
Name of the service to change the mode.
Definition at line 115 of file rb1_base_pad.cpp.
std::string RB1BasePad::cmd_topic_ptz_ [private] |
Name of the topic where it will be publishing the pant-tilt values.
Definition at line 98 of file rb1_base_pad.cpp.
std::string RB1BasePad::cmd_topic_vel_ [private] |
Name of the topic where it will be publishing the velocity.
Definition at line 92 of file rb1_base_pad.cpp.
double RB1BasePad::current_vel [private] |
Definition at line 99 of file rb1_base_pad.cpp.
int RB1BasePad::dead_man_button_ [private] |
Number of the DEADMAN button.
Definition at line 101 of file rb1_base_pad.cpp.
ros::ServiceClient RB1BasePad::doHome [private] |
Service to start homing.
Definition at line 119 of file rb1_base_pad.cpp.
std::string RB1BasePad::elevator_service_name_ [private] |
Name of the service where to actuate the elevator.
Definition at line 96 of file rb1_base_pad.cpp.
int RB1BasePad::kinematic_mode_ [private] |
kinematic mode
Definition at line 111 of file rb1_base_pad.cpp.
double RB1BasePad::l_scale_ [private] |
Definition at line 86 of file rb1_base_pad.cpp.
double RB1BasePad::l_scale_z_ [private] |
Definition at line 86 of file rb1_base_pad.cpp.
int RB1BasePad::linear_x_ [private] |
Definition at line 85 of file rb1_base_pad.cpp.
int RB1BasePad::linear_y_ [private] |
Definition at line 85 of file rb1_base_pad.cpp.
int RB1BasePad::linear_z_ [private] |
Definition at line 85 of file rb1_base_pad.cpp.
double RB1BasePad::max_freq_command [private] |
Diagnostics max freq.
Definition at line 145 of file rb1_base_pad.cpp.
double RB1BasePad::max_freq_joy [private] |
Definition at line 145 of file rb1_base_pad.cpp.
double RB1BasePad::min_freq_command [private] |
Diagnostics min freq.
Definition at line 143 of file rb1_base_pad.cpp.
double RB1BasePad::min_freq_joy [private] |
Definition at line 143 of file rb1_base_pad.cpp.
ros::NodeHandle RB1BasePad::nh_ [private] |
Definition at line 83 of file rb1_base_pad.cpp.
int RB1BasePad::num_of_buttons_ [private] |
Number of buttons of the joystick.
Definition at line 132 of file rb1_base_pad.cpp.
int RB1BasePad::output_1_ [private] |
Definition at line 106 of file rb1_base_pad.cpp.
int RB1BasePad::output_2_ [private] |
Definition at line 106 of file rb1_base_pad.cpp.
ros::Subscriber RB1BasePad::pad_sub_ [private] |
It will be suscribed to the joystick.
Definition at line 90 of file rb1_base_pad.cpp.
int RB1BasePad::pan_increment_ [private] |
Flag to enable/disable the communication with the publishers topics.
Client of the sound play service Pan & tilt increment (degrees)
Definition at line 151 of file rb1_base_pad.cpp.
int RB1BasePad::ptz_pan_left_ [private] |
Definition at line 123 of file rb1_base_pad.cpp.
int RB1BasePad::ptz_pan_right_ [private] |
Definition at line 123 of file rb1_base_pad.cpp.
ros::Publisher RB1BasePad::ptz_pub_ [private] |
Definition at line 88 of file rb1_base_pad.cpp.
int RB1BasePad::ptz_tilt_down_ [private] |
Definition at line 123 of file rb1_base_pad.cpp.
int RB1BasePad::ptz_tilt_up_ [private] |
buttons to the pan-tilt-zoom camera
Definition at line 123 of file rb1_base_pad.cpp.
Diagnostic to control the frequency of the published command velocity topic.
Definition at line 137 of file rb1_base_pad.cpp.
Enables/disables the pad.
Service to modify the digital outputs
Definition at line 128 of file rb1_base_pad.cpp.
Service to activate the elevator.
Definition at line 130 of file rb1_base_pad.cpp.
Service to modify the kinematic mode.
Definition at line 113 of file rb1_base_pad.cpp.
int RB1BasePad::speed_down_button_ [private] |
Definition at line 103 of file rb1_base_pad.cpp.
int RB1BasePad::speed_up_button_ [private] |
Number of the button for increase or decrease the speed max of the joystick.
Definition at line 103 of file rb1_base_pad.cpp.
Diagnostic to control the reception frequency of the subscribed joy topic.
Definition at line 139 of file rb1_base_pad.cpp.
int RB1BasePad::tilt_increment_ [private] |
Definition at line 151 of file rb1_base_pad.cpp.
General status diagnostic updater.
Definition at line 141 of file rb1_base_pad.cpp.
ros::Publisher RB1BasePad::vel_pub_ [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.