Public Member Functions | Private Member Functions | Private Attributes
RbcarJoy Class Reference

List of all members.

Public Member Functions

void ControlLoop ()
 Controls the actions and states.
 RbcarJoy ()
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.
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.
bool bOutput1
bool bOutput2
int button_dead_man_
 Number of the DEADMAN button.
int button_kinematic_mode_
 button to change kinematic mode
int button_speed_down_
int button_speed_up_
 Number of the button for increase or decrease the speed max of the joystick.
std::string cmd_service_io_
 Name of the service where it will be modifying the digital outputs.
std::string cmd_service_ptz_
 Name of the service to move ptz.
std::string cmd_set_mode_
 Name of the service to change the mode.
std::string cmd_topic_vel
 Name of the topic where it will be publishing the velocity.
double current_speed_lvl
double desired_freq_
 Desired component's freq.
ros::ServiceServer enable_disable_srv_
 Service clients.
std::vector< float > fAxes
 Vector to save the axis values.
ros::Subscriber joy_sub_
 they will be suscribed to the joysticks
std::string joy_topic_
 // Name of the joystick's topic
int kinematic_mode_
 kinematic mode
double l_scale_
double max_angular_position_
double max_freq_command
 Diagnostics max freq.
double max_freq_joy
double max_linear_speed_
 Set the max speed sent to the robot.
double min_freq_command
 Diagnostics min freq.
double min_freq_joy
ros::NodeHandle nh_
int num_of_axes_
int num_of_buttons_
 Current number of buttons of the joystick.
int output_1_
int output_2_
int ptz_pan_left_
int ptz_pan_right_
int ptz_tilt_down_
int ptz_tilt_up_
 buttons to the pan-tilt camera
diagnostic_updater::HeaderlessTopicDiagnosticpub_command_freq
 Diagnostic to control the frequency of the published command velocity topic.
ros::ServiceClient set_digital_outputs_client_
ros::ServiceClient setKinematicMode
 Service to modify the kinematic mode.
ros::Publisher state_pub_
 Topic to publish the state.
diagnostic_updater::HeaderlessTopicDiagnosticsus_joy_freq
 Diagnostic to control the reception frequency of the subscribed joy topic.
std::string topic_state_
 topic name for the state
diagnostic_updater::Updater updater_pad
 General status diagnostic updater.
std::vector< ButtonvButtons
 Vector to save and control the axis values.
ros::Publisher vel_pub_
 It will publish into command velocity (for the robot)

Detailed Description

Definition at line 106 of file rbcar_joystick.cpp.


Constructor & Destructor Documentation

Definition at line 202 of file rbcar_joystick.cpp.


Member Function Documentation

Controls the actions and states.

Definition at line 360 of file rbcar_joystick.cpp.

bool RbcarJoy::EnableDisable ( robotnik_msgs::enable_disable::Request &  req,
robotnik_msgs::enable_disable::Response &  res 
) [private]

Enables/Disables the joystick.

Definition at line 336 of file rbcar_joystick.cpp.

void RbcarJoy::joyCallback ( const sensor_msgs::Joy::ConstPtr &  joy) [private]

Definition at line 345 of file rbcar_joystick.cpp.

void RbcarJoy::PublishState ( ) [private]

Definition at line 321 of file rbcar_joystick.cpp.

int RbcarJoy::SetStateMode ( int  state,
int  arm_mode,
int  platform_mode 
)
char* RbcarJoy::StateToString ( int  state) [private]
int RbcarJoy::SwitchToState ( int  new_state) [private]
void RbcarJoy::Update ( ) [private]

Definition at line 316 of file rbcar_joystick.cpp.


Member Data Documentation

double RbcarJoy::a_scale_ [private]

Definition at line 131 of file rbcar_joystick.cpp.

Definition at line 130 of file rbcar_joystick.cpp.

Definition at line 130 of file rbcar_joystick.cpp.

bool RbcarJoy::bEnable [private]

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

Definition at line 199 of file rbcar_joystick.cpp.

bool RbcarJoy::bOutput1 [private]

Definition at line 173 of file rbcar_joystick.cpp.

bool RbcarJoy::bOutput2 [private]

Definition at line 173 of file rbcar_joystick.cpp.

Number of the DEADMAN button.

Definition at line 169 of file rbcar_joystick.cpp.

button to change kinematic mode

Definition at line 179 of file rbcar_joystick.cpp.

Definition at line 171 of file rbcar_joystick.cpp.

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

Definition at line 171 of file rbcar_joystick.cpp.

std::string RbcarJoy::cmd_service_io_ [private]

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

Definition at line 148 of file rbcar_joystick.cpp.

std::string RbcarJoy::cmd_service_ptz_ [private]

Name of the service to move ptz.

Definition at line 177 of file rbcar_joystick.cpp.

std::string RbcarJoy::cmd_set_mode_ [private]

Name of the service to change the mode.

Definition at line 185 of file rbcar_joystick.cpp.

std::string RbcarJoy::cmd_topic_vel [private]

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

Definition at line 146 of file rbcar_joystick.cpp.

double RbcarJoy::current_speed_lvl [private]

Definition at line 132 of file rbcar_joystick.cpp.

double RbcarJoy::desired_freq_ [private]

Desired component's freq.

Definition at line 136 of file rbcar_joystick.cpp.

Service clients.

Definition at line 156 of file rbcar_joystick.cpp.

std::vector<float> RbcarJoy::fAxes [private]

Vector to save the axis values.

Definition at line 165 of file rbcar_joystick.cpp.

they will be suscribed to the joysticks

Definition at line 142 of file rbcar_joystick.cpp.

std::string RbcarJoy::joy_topic_ [private]

// Name of the joystick's topic

Definition at line 144 of file rbcar_joystick.cpp.

kinematic mode

Definition at line 181 of file rbcar_joystick.cpp.

double RbcarJoy::l_scale_ [private]

Definition at line 131 of file rbcar_joystick.cpp.

Definition at line 134 of file rbcar_joystick.cpp.

double RbcarJoy::max_freq_command [private]

Diagnostics max freq.

Definition at line 197 of file rbcar_joystick.cpp.

double RbcarJoy::max_freq_joy [private]

Definition at line 197 of file rbcar_joystick.cpp.

double RbcarJoy::max_linear_speed_ [private]

Set the max speed sent to the robot.

Definition at line 134 of file rbcar_joystick.cpp.

double RbcarJoy::min_freq_command [private]

Diagnostics min freq.

Definition at line 195 of file rbcar_joystick.cpp.

double RbcarJoy::min_freq_joy [private]

Definition at line 195 of file rbcar_joystick.cpp.

Definition at line 128 of file rbcar_joystick.cpp.

int RbcarJoy::num_of_axes_ [private]

Definition at line 162 of file rbcar_joystick.cpp.

Current number of buttons of the joystick.

Definition at line 161 of file rbcar_joystick.cpp.

int RbcarJoy::output_1_ [private]

Definition at line 172 of file rbcar_joystick.cpp.

int RbcarJoy::output_2_ [private]

Definition at line 172 of file rbcar_joystick.cpp.

int RbcarJoy::ptz_pan_left_ [private]

Definition at line 175 of file rbcar_joystick.cpp.

int RbcarJoy::ptz_pan_right_ [private]

Definition at line 175 of file rbcar_joystick.cpp.

int RbcarJoy::ptz_tilt_down_ [private]

Definition at line 175 of file rbcar_joystick.cpp.

int RbcarJoy::ptz_tilt_up_ [private]

buttons to the pan-tilt camera

Definition at line 175 of file rbcar_joystick.cpp.

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

Definition at line 189 of file rbcar_joystick.cpp.

Definition at line 157 of file rbcar_joystick.cpp.

Service to modify the kinematic mode.

Definition at line 183 of file rbcar_joystick.cpp.

Topic to publish the state.

Definition at line 152 of file rbcar_joystick.cpp.

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

Definition at line 191 of file rbcar_joystick.cpp.

std::string RbcarJoy::topic_state_ [private]

topic name for the state

Definition at line 150 of file rbcar_joystick.cpp.

General status diagnostic updater.

Definition at line 193 of file rbcar_joystick.cpp.

std::vector<Button> RbcarJoy::vButtons [private]

Vector to save and control the axis values.

Definition at line 167 of file rbcar_joystick.cpp.

It will publish into command velocity (for the robot)

Definition at line 140 of file rbcar_joystick.cpp.


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


rbcar_joystick
Author(s): Roberto Guzman
autogenerated on Thu Jun 6 2019 19:55:48