Keyboard remote control for our robot core (mobile base). More...
#include <keyop_core.hpp>
Public Member Functions | |
bool | init () |
Initialises the node. | |
KeyOpCore () | |
Default constructor, needs initialisation. | |
void | spin () |
Worker thread loop; sends current velocity command at a fixed rate. | |
~KeyOpCore () | |
Private Member Functions | |
void | decrementAngularVelocity () |
If not already mined, decrement the angular velocities.. | |
void | decrementLinearVelocity () |
If not already minned, decrement the linear velocities.. | |
void | disable () |
Disables commands to the navigation system. | |
void | enable () |
Reset/re-enable the navigation system. | |
void | incrementAngularVelocity () |
If not already maxxed, increment the angular velocities.. | |
void | incrementLinearVelocity () |
If not already maxxed, increment the command velocities.. | |
void | keyboardInputLoop () |
The worker thread function that accepts input keyboard commands. | |
void | processKeyboardInput (char c) |
Process individual keyboard inputs. | |
void | remoteKeyInputReceived (const kobuki_msgs::KeyboardInput &key) |
Callback function for remote keyboard inputs subscriber. | |
void | resetVelocity () |
void | restoreTerminal () |
Private Attributes | |
bool | accept_incoming |
double | angular_vel_max |
double | angular_vel_step |
geometry_msgs::TwistPtr | cmd |
geometry_msgs::TwistStampedPtr | cmd_stamped |
int | key_file_descriptor |
ros::Subscriber | keyinput_subscriber |
bool | last_zero_vel_sent |
double | linear_vel_max |
double | linear_vel_step |
ros::Publisher | motor_power_publisher_ |
std::string | name |
struct termios | original_terminal_state |
bool | power_status |
bool | quit_requested |
ecl::Thread | thread |
ros::Publisher | velocity_publisher_ |
bool | wait_for_connection_ |
Keyboard remote control for our robot core (mobile base).
Definition at line 69 of file keyop_core.hpp.
Default constructor, needs initialisation.
Definition at line 62 of file keyop_core.cpp.
Definition at line 78 of file keyop_core.cpp.
void keyop_core::KeyOpCore::decrementAngularVelocity | ( | ) | [private] |
If not already mined, decrement the angular velocities..
Definition at line 460 of file keyop_core.cpp.
void keyop_core::KeyOpCore::decrementLinearVelocity | ( | ) | [private] |
If not already minned, decrement the linear velocities..
Definition at line 422 of file keyop_core.cpp.
void keyop_core::KeyOpCore::disable | ( | ) | [private] |
Disables commands to the navigation system.
This does the following things:
msg |
Definition at line 351 of file keyop_core.cpp.
void keyop_core::KeyOpCore::enable | ( | ) | [private] |
Reset/re-enable the navigation system.
Definition at line 378 of file keyop_core.cpp.
void keyop_core::KeyOpCore::incrementAngularVelocity | ( | ) | [private] |
If not already maxxed, increment the angular velocities..
Definition at line 441 of file keyop_core.cpp.
void keyop_core::KeyOpCore::incrementLinearVelocity | ( | ) | [private] |
If not already maxxed, increment the command velocities..
Definition at line 403 of file keyop_core.cpp.
bool keyop_core::KeyOpCore::init | ( | ) |
Initialises the node.
Definition at line 86 of file keyop_core.cpp.
void keyop_core::KeyOpCore::keyboardInputLoop | ( | ) | [private] |
The worker thread function that accepts input keyboard commands.
This is ok here - but later it might be a good idea to make a node which posts keyboard events to a topic. Recycle common code if used by many!
Definition at line 238 of file keyop_core.cpp.
void keyop_core::KeyOpCore::processKeyboardInput | ( | char | c | ) | [private] |
Process individual keyboard inputs.
c | keyboard input. |
Definition at line 282 of file keyop_core.cpp.
void keyop_core::KeyOpCore::remoteKeyInputReceived | ( | const kobuki_msgs::KeyboardInput & | key | ) | [private] |
Callback function for remote keyboard inputs subscriber.
Definition at line 272 of file keyop_core.cpp.
void keyop_core::KeyOpCore::resetVelocity | ( | ) | [private] |
Definition at line 476 of file keyop_core.cpp.
void keyop_core::KeyOpCore::restoreTerminal | ( | ) | [private] |
void keyop_core::KeyOpCore::spin | ( | ) |
Worker thread loop; sends current velocity command at a fixed rate.
It also process ros functions as well as aborting when requested.
Definition at line 193 of file keyop_core.cpp.
bool keyop_core::KeyOpCore::accept_incoming [private] |
Definition at line 89 of file keyop_core.hpp.
double keyop_core::KeyOpCore::angular_vel_max [private] |
Definition at line 95 of file keyop_core.hpp.
double keyop_core::KeyOpCore::angular_vel_step [private] |
Definition at line 95 of file keyop_core.hpp.
geometry_msgs::TwistPtr keyop_core::KeyOpCore::cmd [private] |
Definition at line 92 of file keyop_core.hpp.
geometry_msgs::TwistStampedPtr keyop_core::KeyOpCore::cmd_stamped [private] |
Definition at line 93 of file keyop_core.hpp.
int keyop_core::KeyOpCore::key_file_descriptor [private] |
Definition at line 118 of file keyop_core.hpp.
Definition at line 85 of file keyop_core.hpp.
bool keyop_core::KeyOpCore::last_zero_vel_sent [private] |
Definition at line 88 of file keyop_core.hpp.
double keyop_core::KeyOpCore::linear_vel_max [private] |
Definition at line 94 of file keyop_core.hpp.
double keyop_core::KeyOpCore::linear_vel_step [private] |
Definition at line 94 of file keyop_core.hpp.
Definition at line 87 of file keyop_core.hpp.
std::string keyop_core::KeyOpCore::name [private] |
Definition at line 96 of file keyop_core.hpp.
struct termios keyop_core::KeyOpCore::original_terminal_state [private] |
Definition at line 119 of file keyop_core.hpp.
bool keyop_core::KeyOpCore::power_status [private] |
Definition at line 90 of file keyop_core.hpp.
bool keyop_core::KeyOpCore::quit_requested [private] |
Definition at line 117 of file keyop_core.hpp.
ecl::Thread keyop_core::KeyOpCore::thread [private] |
Definition at line 120 of file keyop_core.hpp.
Definition at line 86 of file keyop_core.hpp.
bool keyop_core::KeyOpCore::wait_for_connection_ [private] |
Definition at line 91 of file keyop_core.hpp.