Public Member Functions | |
void | ControlLoop () |
Controls the actions and states. More... | |
RbcarPad () | |
int | SetStateMode (int state, int arm_mode, int platform_mode) |
Private Member Functions | |
bool | EnableDisable (robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res) |
Enables/Disables the joystick. More... | |
void | joyCallback (const sensor_msgs::Joy::ConstPtr &joy) |
void | PublishState () |
char * | StateToString (int state) |
int | SwitchToState (int new_state) |
void | Update () |
Private Attributes | |
double | a_scale_ |
int | axis_angular_position_ |
int | axis_linear_speed_ |
bool | bEnable |
Flag to enable/disable the communication with the publishers topics. More... | |
bool | bOutput1 |
bool | bOutput2 |
int | button_dead_man_ |
Number of the DEADMAN button. More... | |
int | button_kinematic_mode_ |
button to change kinematic mode More... | |
int | button_speed_down_ |
int | button_speed_up_ |
Number of the button for increase or decrease the speed max of the joystick. More... | |
std::string | cmd_service_io_ |
Name of the service where it will be modifying the digital outputs. More... | |
std::string | cmd_service_ptz_ |
Name of the service to move ptz. More... | |
std::string | cmd_set_mode_ |
Name of the service to change the mode. More... | |
std::string | cmd_topic_vel |
Name of the topic where it will be publishing the velocity. More... | |
double | current_speed_lvl |
double | desired_freq_ |
Desired component's freq. More... | |
ros::ServiceServer | enable_disable_srv_ |
Service clients. More... | |
std::vector< float > | fAxes |
Vector to save the axis values. More... | |
ros::Subscriber | joy_sub_ |
they will be suscribed to the joysticks More... | |
std::string | joy_topic_ |
// Name of the joystick's topic More... | |
int | kinematic_mode_ |
kinematic mode More... | |
double | l_scale_ |
double | max_angular_position_ |
double | max_freq_command |
Diagnostics max freq. More... | |
double | max_freq_joy |
double | max_linear_speed_ |
Set the max speed sent to the robot. More... | |
double | min_freq_command |
Diagnostics min freq. More... | |
double | min_freq_joy |
ros::NodeHandle | nh_ |
int | num_of_axes_ |
int | num_of_buttons_ |
Current number of buttons of the joystick. More... | |
int | output_1_ |
int | output_2_ |
ros::NodeHandle | pnh_ |
int | ptz_pan_left_ |
int | ptz_pan_right_ |
int | ptz_tilt_down_ |
int | ptz_tilt_up_ |
buttons to the pan-tilt 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_ |
ros::ServiceClient | setKinematicMode |
Service to modify the kinematic mode. More... | |
ros::Publisher | state_pub_ |
Topic to publish the state. More... | |
diagnostic_updater::HeaderlessTopicDiagnostic * | sus_joy_freq |
Diagnostic to control the reception frequency of the subscribed joy topic. More... | |
std::string | topic_state_ |
topic name for the state More... | |
diagnostic_updater::Updater | updater_pad |
General status diagnostic updater. More... | |
std::vector< Button > | vButtons |
Vector to save and control the axis values. More... | |
ros::Publisher | vel_pub_ |
It will publish into command velocity (for the robot) More... | |
Definition at line 109 of file rbcar_pad.cpp.
RbcarPad::RbcarPad | ( | ) |
Definition at line 203 of file rbcar_pad.cpp.
void RbcarPad::ControlLoop | ( | ) |
Controls the actions and states.
Definition at line 350 of file rbcar_pad.cpp.
|
private |
Enables/Disables the joystick.
Definition at line 324 of file rbcar_pad.cpp.
|
private |
Definition at line 333 of file rbcar_pad.cpp.
|
private |
Definition at line 308 of file rbcar_pad.cpp.
int RbcarPad::SetStateMode | ( | int | state, |
int | arm_mode, | ||
int | platform_mode | ||
) |
|
private |
|
private |
|
private |
Definition at line 302 of file rbcar_pad.cpp.
|
private |
Definition at line 132 of file rbcar_pad.cpp.
|
private |
Definition at line 131 of file rbcar_pad.cpp.
|
private |
Definition at line 131 of file rbcar_pad.cpp.
|
private |
Flag to enable/disable the communication with the publishers topics.
Definition at line 200 of file rbcar_pad.cpp.
|
private |
Definition at line 174 of file rbcar_pad.cpp.
|
private |
Definition at line 174 of file rbcar_pad.cpp.
|
private |
Number of the DEADMAN button.
Definition at line 170 of file rbcar_pad.cpp.
|
private |
button to change kinematic mode
Definition at line 180 of file rbcar_pad.cpp.
|
private |
Definition at line 172 of file rbcar_pad.cpp.
|
private |
Number of the button for increase or decrease the speed max of the joystick.
Definition at line 172 of file rbcar_pad.cpp.
|
private |
Name of the service where it will be modifying the digital outputs.
Definition at line 149 of file rbcar_pad.cpp.
|
private |
Name of the service to move ptz.
Definition at line 178 of file rbcar_pad.cpp.
|
private |
Name of the service to change the mode.
Definition at line 186 of file rbcar_pad.cpp.
|
private |
Name of the topic where it will be publishing the velocity.
Definition at line 147 of file rbcar_pad.cpp.
|
private |
Definition at line 133 of file rbcar_pad.cpp.
|
private |
Desired component's freq.
Definition at line 137 of file rbcar_pad.cpp.
|
private |
Service clients.
Definition at line 157 of file rbcar_pad.cpp.
|
private |
Vector to save the axis values.
Definition at line 166 of file rbcar_pad.cpp.
|
private |
they will be suscribed to the joysticks
Definition at line 143 of file rbcar_pad.cpp.
|
private |
// Name of the joystick's topic
Definition at line 145 of file rbcar_pad.cpp.
|
private |
kinematic mode
Definition at line 182 of file rbcar_pad.cpp.
|
private |
Definition at line 132 of file rbcar_pad.cpp.
|
private |
Definition at line 135 of file rbcar_pad.cpp.
|
private |
Diagnostics max freq.
Definition at line 198 of file rbcar_pad.cpp.
|
private |
Definition at line 198 of file rbcar_pad.cpp.
|
private |
Set the max speed sent to the robot.
Definition at line 135 of file rbcar_pad.cpp.
|
private |
Diagnostics min freq.
Definition at line 196 of file rbcar_pad.cpp.
|
private |
Definition at line 196 of file rbcar_pad.cpp.
|
private |
Definition at line 129 of file rbcar_pad.cpp.
|
private |
Definition at line 163 of file rbcar_pad.cpp.
|
private |
Current number of buttons of the joystick.
Definition at line 162 of file rbcar_pad.cpp.
|
private |
Definition at line 173 of file rbcar_pad.cpp.
|
private |
Definition at line 173 of file rbcar_pad.cpp.
|
private |
Definition at line 129 of file rbcar_pad.cpp.
|
private |
Definition at line 176 of file rbcar_pad.cpp.
|
private |
Definition at line 176 of file rbcar_pad.cpp.
|
private |
Definition at line 176 of file rbcar_pad.cpp.
|
private |
buttons to the pan-tilt camera
Definition at line 176 of file rbcar_pad.cpp.
|
private |
Diagnostic to control the frequency of the published command velocity topic.
Definition at line 190 of file rbcar_pad.cpp.
|
private |
Definition at line 158 of file rbcar_pad.cpp.
|
private |
Service to modify the kinematic mode.
Definition at line 184 of file rbcar_pad.cpp.
|
private |
Topic to publish the state.
Definition at line 153 of file rbcar_pad.cpp.
|
private |
Diagnostic to control the reception frequency of the subscribed joy topic.
Definition at line 192 of file rbcar_pad.cpp.
|
private |
topic name for the state
Definition at line 151 of file rbcar_pad.cpp.
|
private |
General status diagnostic updater.
Definition at line 194 of file rbcar_pad.cpp.
|
private |
Vector to save and control the axis values.
Definition at line 168 of file rbcar_pad.cpp.
|
private |
It will publish into command velocity (for the robot)
Definition at line 141 of file rbcar_pad.cpp.