Public Member Functions | |
AgvsPad () | |
void | ControlLoop () |
Controls the actions and states. | |
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_down_car_ |
int | button_speed_down_ |
int | button_speed_up_ |
Number of the button for increase or decrease the speed max of the joystick. | |
int | button_up_car_ |
std::string | cmd_service_io_ |
Name of the service where it will be modifying the digital outputs. | |
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 | |
double | l_scale_ |
ros::ServiceClient | lower_elevator_client_ |
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_ |
diagnostic_updater::HeaderlessTopicDiagnostic * | pub_command_freq |
Diagnostic to control the frequency of the published command velocity topic. | |
ros::ServiceClient | raise_elevator_client_ |
std::string | service_lower_elevator_ |
Name of the service called to lower the elevator. | |
std::string | service_raise_elevator_ |
Name of the service called to raise the elevator. | |
ros::ServiceClient | set_digital_outputs_client_ |
ros::Publisher | state_pub_ |
Topic to publish the state. | |
diagnostic_updater::HeaderlessTopicDiagnostic * | sus_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< Button > | vButtons |
Vector to save and control the axis values. | |
ros::Publisher | vel_pub_ |
It will publish into command velocity (for the robot) |
Definition at line 113 of file agvs_pad_node.cpp.
AgvsPad::AgvsPad | ( | ) |
Definition at line 209 of file agvs_pad_node.cpp.
void AgvsPad::ControlLoop | ( | ) |
Controls the actions and states.
Definition at line 359 of file agvs_pad_node.cpp.
bool AgvsPad::EnableDisable | ( | robotnik_msgs::enable_disable::Request & | req, |
robotnik_msgs::enable_disable::Response & | res | ||
) | [private] |
Enables/Disables the joystick.
Definition at line 330 of file agvs_pad_node.cpp.
void AgvsPad::joyCallback | ( | const sensor_msgs::Joy::ConstPtr & | joy | ) | [private] |
Definition at line 340 of file agvs_pad_node.cpp.
void AgvsPad::PublishState | ( | ) | [private] |
Definition at line 321 of file agvs_pad_node.cpp.
int AgvsPad::SetStateMode | ( | int | state, |
int | arm_mode, | ||
int | platform_mode | ||
) |
char* AgvsPad::StateToString | ( | int | state | ) | [private] |
int AgvsPad::SwitchToState | ( | int | new_state | ) | [private] |
void AgvsPad::Update | ( | ) | [private] |
Definition at line 316 of file agvs_pad_node.cpp.
double AgvsPad::a_scale_ [private] |
Definition at line 139 of file agvs_pad_node.cpp.
int AgvsPad::axis_angular_position_ [private] |
Definition at line 138 of file agvs_pad_node.cpp.
int AgvsPad::axis_linear_speed_ [private] |
Definition at line 138 of file agvs_pad_node.cpp.
bool AgvsPad::bEnable [private] |
Flag to enable/disable the communication with the publishers topics.
Definition at line 205 of file agvs_pad_node.cpp.
bool AgvsPad::bOutput1 [private] |
Definition at line 191 of file agvs_pad_node.cpp.
bool AgvsPad::bOutput2 [private] |
Definition at line 191 of file agvs_pad_node.cpp.
int AgvsPad::button_dead_man_ [private] |
Number of the DEADMAN button.
Definition at line 186 of file agvs_pad_node.cpp.
int AgvsPad::button_down_car_ [private] |
Definition at line 189 of file agvs_pad_node.cpp.
int AgvsPad::button_speed_down_ [private] |
Definition at line 188 of file agvs_pad_node.cpp.
int AgvsPad::button_speed_up_ [private] |
Number of the button for increase or decrease the speed max of the joystick.
Definition at line 188 of file agvs_pad_node.cpp.
int AgvsPad::button_up_car_ [private] |
Definition at line 189 of file agvs_pad_node.cpp.
std::string AgvsPad::cmd_service_io_ [private] |
Name of the service where it will be modifying the digital outputs.
Definition at line 157 of file agvs_pad_node.cpp.
std::string AgvsPad::cmd_topic_vel [private] |
Name of the topic where it will be publishing the velocity.
Definition at line 155 of file agvs_pad_node.cpp.
double AgvsPad::current_speed_lvl [private] |
Definition at line 140 of file agvs_pad_node.cpp.
double AgvsPad::desired_freq_ [private] |
Desired component's freq.
Definition at line 144 of file agvs_pad_node.cpp.
Service clients.
Definition at line 170 of file agvs_pad_node.cpp.
std::vector<float> AgvsPad::fAxes [private] |
Vector to save the axis values.
Definition at line 182 of file agvs_pad_node.cpp.
ros::Subscriber AgvsPad::joy_sub_ [private] |
they will be suscribed to the joysticks
Definition at line 151 of file agvs_pad_node.cpp.
std::string AgvsPad::joy_topic_ [private] |
// Name of the joystick's topic
Definition at line 153 of file agvs_pad_node.cpp.
double AgvsPad::l_scale_ [private] |
Definition at line 139 of file agvs_pad_node.cpp.
Definition at line 173 of file agvs_pad_node.cpp.
double AgvsPad::max_angular_position_ [private] |
Definition at line 142 of file agvs_pad_node.cpp.
double AgvsPad::max_freq_command [private] |
Diagnostics max freq.
Definition at line 203 of file agvs_pad_node.cpp.
double AgvsPad::max_freq_joy [private] |
Definition at line 203 of file agvs_pad_node.cpp.
double AgvsPad::max_linear_speed_ [private] |
Set the max speed sent to the robot.
Definition at line 142 of file agvs_pad_node.cpp.
double AgvsPad::min_freq_command [private] |
Diagnostics min freq.
Definition at line 201 of file agvs_pad_node.cpp.
double AgvsPad::min_freq_joy [private] |
Definition at line 201 of file agvs_pad_node.cpp.
ros::NodeHandle AgvsPad::nh_ [private] |
Definition at line 136 of file agvs_pad_node.cpp.
int AgvsPad::num_of_axes_ [private] |
Definition at line 179 of file agvs_pad_node.cpp.
int AgvsPad::num_of_buttons_ [private] |
Current number of buttons of the joystick.
Definition at line 178 of file agvs_pad_node.cpp.
int AgvsPad::output_1_ [private] |
Definition at line 190 of file agvs_pad_node.cpp.
int AgvsPad::output_2_ [private] |
Definition at line 190 of file agvs_pad_node.cpp.
Diagnostic to control the frequency of the published command velocity topic.
Definition at line 195 of file agvs_pad_node.cpp.
Definition at line 172 of file agvs_pad_node.cpp.
std::string AgvsPad::service_lower_elevator_ [private] |
Name of the service called to lower the elevator.
Definition at line 166 of file agvs_pad_node.cpp.
std::string AgvsPad::service_raise_elevator_ [private] |
Name of the service called to raise the elevator.
Definition at line 164 of file agvs_pad_node.cpp.
Definition at line 171 of file agvs_pad_node.cpp.
ros::Publisher AgvsPad::state_pub_ [private] |
Topic to publish the state.
Definition at line 161 of file agvs_pad_node.cpp.
Diagnostic to control the reception frequency of the subscribed joy topic.
Definition at line 197 of file agvs_pad_node.cpp.
std::string AgvsPad::topic_state_ [private] |
topic name for the state
Definition at line 159 of file agvs_pad_node.cpp.
General status diagnostic updater.
Definition at line 199 of file agvs_pad_node.cpp.
std::vector<Button> AgvsPad::vButtons [private] |
Vector to save and control the axis values.
Definition at line 184 of file agvs_pad_node.cpp.
ros::Publisher AgvsPad::vel_pub_ [private] |
It will publish into command velocity (for the robot)
Definition at line 148 of file agvs_pad_node.cpp.