keyop.hpp
Go to the documentation of this file.
1 
6 #ifndef YOCS_KEYOP_KEYOP_HPP_
7 #define YOCS_KEYOP_KEYOP_HPP_
8 
9 #include <ros/ros.h>
10 #include <termios.h> // for keyboard input
11 #include <ecl/threads.hpp>
12 #include <geometry_msgs/Twist.h> // for velocity commands
13 #include <geometry_msgs/TwistStamped.h> // for velocity commands
14 
15 
16 namespace yocs_keyop
17 {
22 class KeyOp
23 {
24 public:
25  /*********************
26  ** C&D
27  **********************/
28  KeyOp();
29  ~KeyOp();
30  bool init();
31 
32  /*********************
33  ** Runtime
34  **********************/
35  void spin();
36 
37 private:
43  geometry_msgs::TwistPtr cmd_;
44  geometry_msgs::TwistStampedPtr cmd_stamped_;
47  std::string name_;
48 
49  /*********************
50  ** Commands
51  **********************/
52  void enable();
53  void disable();
58  void resetVelocity();
59 
60  /*********************
61  ** Keylogging
62  **********************/
63 
64  void keyboardInputLoop();
65  void processKeyboardInput(char c);
66  void restoreTerminal();
69  struct termios original_terminal_state_;
70  ecl::Thread thread_;
71 };
72 
73 } // namespace yocs_keyop
74 
75 #endif /* YOCS_KEYOP_KEYOP_HPP_ */
bool quit_requested_
Definition: keyop.hpp:67
double linear_vel_max_
Definition: keyop.hpp:45
ros::Publisher disable_motors_publisher_
Definition: keyop.hpp:38
ros::Publisher velocity_publisher_
Definition: keyop.hpp:38
void keyboardInputLoop()
The worker thread function that accepts input keyboard commands.
Definition: keyop.cpp:195
void enable()
Reset/re-enable the navigation system.
Definition: keyop.cpp:327
ros::Publisher enable_motors_publisher_
Definition: keyop.hpp:38
void decrementLinearVelocity()
If not already minned, decrement the linear velocities..
Definition: keyop.cpp:370
bool power_status_
Definition: keyop.hpp:41
void spin()
Worker thread loop; sends current velocity command at a fixed rate.
Definition: keyop.cpp:150
int key_file_descriptor_
Definition: keyop.hpp:68
void incrementAngularVelocity()
If not already maxxed, increment the angular velocities..
Definition: keyop.cpp:389
bool accept_incoming_
Definition: keyop.hpp:40
double linear_vel_step_
Definition: keyop.hpp:45
void processKeyboardInput(char c)
Process individual keyboard inputs.
Definition: keyop.cpp:231
Keyboard remote control for your robot.
Definition: keyop.hpp:22
geometry_msgs::TwistStampedPtr cmd_stamped_
Definition: keyop.hpp:44
std::string name_
Definition: keyop.hpp:47
double angular_vel_max_
Definition: keyop.hpp:46
ecl::Thread thread_
Definition: keyop.hpp:70
void incrementLinearVelocity()
If not already maxxed, increment the command velocities..
Definition: keyop.cpp:351
void resetVelocity()
Definition: keyop.cpp:424
struct termios original_terminal_state_
Definition: keyop.hpp:69
double angular_vel_step_
Definition: keyop.hpp:46
bool last_zero_vel_sent_
Definition: keyop.hpp:39
bool wait_for_connection_
Definition: keyop.hpp:42
geometry_msgs::TwistPtr cmd_
Definition: keyop.hpp:43
bool init()
Initialises the node.
Definition: keyop.cpp:46
void disable()
Disables commands to the navigation system.
Definition: keyop.cpp:300
void decrementAngularVelocity()
If not already mined, decrement the angular velocities..
Definition: keyop.cpp:408


yocs_keyop
Author(s): Daniel Stonier, Marcus Liebhardt
autogenerated on Mon Jun 10 2019 15:53:34