Keyboard remote control for our robot core (mobile base).
More...
#include <keyop_core.hpp>
Keyboard remote control for our robot core (mobile base).
Definition at line 69 of file keyop_core.hpp.
keyop_core::KeyOpCore::KeyOpCore |
( |
| ) |
|
Default constructor, needs initialisation.
Definition at line 62 of file keyop_core.cpp.
keyop_core::KeyOpCore::~KeyOpCore |
( |
| ) |
|
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:
- Disables power to the navigation motors (via device_manager).
- Parameters
-
Definition at line 351 of file keyop_core.cpp.
void keyop_core::KeyOpCore::enable |
( |
| ) |
|
|
private |
Reset/re-enable the navigation system.
- resets the command velocities.
- reenable power if not enabled.
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 |
( |
| ) |
|
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.
- Parameters
-
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 |
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 |
double keyop_core::KeyOpCore::angular_vel_max |
|
private |
double keyop_core::KeyOpCore::angular_vel_step |
|
private |
geometry_msgs::TwistPtr keyop_core::KeyOpCore::cmd |
|
private |
geometry_msgs::TwistStampedPtr keyop_core::KeyOpCore::cmd_stamped |
|
private |
int keyop_core::KeyOpCore::key_file_descriptor |
|
private |
bool keyop_core::KeyOpCore::last_zero_vel_sent |
|
private |
double keyop_core::KeyOpCore::linear_vel_max |
|
private |
double keyop_core::KeyOpCore::linear_vel_step |
|
private |
std::string keyop_core::KeyOpCore::name |
|
private |
struct termios keyop_core::KeyOpCore::original_terminal_state |
|
private |
bool keyop_core::KeyOpCore::power_status |
|
private |
bool keyop_core::KeyOpCore::quit_requested |
|
private |
ecl::Thread keyop_core::KeyOpCore::thread |
|
private |
bool keyop_core::KeyOpCore::wait_for_connection_ |
|
private |
The documentation for this class was generated from the following files: