Keyboard remote control for your robot.
More...
#include <keyop.hpp>
Keyboard remote control for your robot.
Definition at line 22 of file keyop.hpp.
yocs_keyop::KeyOp::KeyOp |
( |
| ) |
|
yocs_keyop::KeyOp::~KeyOp |
( |
| ) |
|
void yocs_keyop::KeyOp::decrementAngularVelocity |
( |
| ) |
|
|
private |
If not already mined, decrement the angular velocities..
Definition at line 408 of file keyop.cpp.
void yocs_keyop::KeyOp::decrementLinearVelocity |
( |
| ) |
|
|
private |
If not already minned, decrement the linear velocities..
Definition at line 370 of file keyop.cpp.
void yocs_keyop::KeyOp::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 300 of file keyop.cpp.
void yocs_keyop::KeyOp::enable |
( |
| ) |
|
|
private |
Reset/re-enable the navigation system.
- resets the command velocities.
- reenable power if not enabled.
Definition at line 327 of file keyop.cpp.
void yocs_keyop::KeyOp::incrementAngularVelocity |
( |
| ) |
|
|
private |
If not already maxxed, increment the angular velocities..
Definition at line 389 of file keyop.cpp.
void yocs_keyop::KeyOp::incrementLinearVelocity |
( |
| ) |
|
|
private |
If not already maxxed, increment the command velocities..
Definition at line 351 of file keyop.cpp.
bool yocs_keyop::KeyOp::init |
( |
| ) |
|
Initialises the node.
Definition at line 46 of file keyop.cpp.
void yocs_keyop::KeyOp::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 195 of file keyop.cpp.
void yocs_keyop::KeyOp::processKeyboardInput |
( |
char |
c | ) |
|
|
private |
Process individual keyboard inputs.
- Parameters
-
Definition at line 231 of file keyop.cpp.
void yocs_keyop::KeyOp::resetVelocity |
( |
| ) |
|
|
private |
void yocs_keyop::KeyOp::restoreTerminal |
( |
| ) |
|
|
private |
void yocs_keyop::KeyOp::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 150 of file keyop.cpp.
bool yocs_keyop::KeyOp::accept_incoming_ |
|
private |
double yocs_keyop::KeyOp::angular_vel_max_ |
|
private |
double yocs_keyop::KeyOp::angular_vel_step_ |
|
private |
geometry_msgs::TwistPtr yocs_keyop::KeyOp::cmd_ |
|
private |
geometry_msgs::TwistStampedPtr yocs_keyop::KeyOp::cmd_stamped_ |
|
private |
int yocs_keyop::KeyOp::key_file_descriptor_ |
|
private |
bool yocs_keyop::KeyOp::last_zero_vel_sent_ |
|
private |
double yocs_keyop::KeyOp::linear_vel_max_ |
|
private |
double yocs_keyop::KeyOp::linear_vel_step_ |
|
private |
std::string yocs_keyop::KeyOp::name_ |
|
private |
struct termios yocs_keyop::KeyOp::original_terminal_state_ |
|
private |
bool yocs_keyop::KeyOp::power_status_ |
|
private |
bool yocs_keyop::KeyOp::quit_requested_ |
|
private |
ecl::Thread yocs_keyop::KeyOp::thread_ |
|
private |
bool yocs_keyop::KeyOp::wait_for_connection_ |
|
private |
The documentation for this class was generated from the following files: