From 286dbb36bf1c673c92ac945c60c176954e45e908 Mon Sep 17 00:00:00 2001 From: Louis-Guillaume DUBOIS Date: Fri, 1 May 2015 21:23:00 +0200 Subject: [PATCH] essai ncurses --- CMakeLists.txt | 11 +++++++++++ src/curses.cpp | 37 +++++++++++++++++++++++++++++++++++++ src/curses.h | 23 +++++++++++++++++++++++ src/keyboard_cmd.cpp | 23 +++++------------------ src/test.cpp | 8 ++++++++ 5 files changed, 84 insertions(+), 18 deletions(-) create mode 100644 src/curses.cpp create mode 100644 src/curses.h create mode 100644 src/test.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 4bc809a..124337e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,6 +9,11 @@ find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation ) +find_package( + PkgConfig REQUIRED +) + +pkg_check_modules ( ncurses REQUIRED ncurses ) add_message_files( FILES @@ -25,6 +30,7 @@ catkin_package() include_directories( ${catkin_INCLUDE_DIRS} + ${CURSES_INCLUDE_DIRS} ) add_executable(filtre src/filtre.cpp) @@ -36,6 +42,11 @@ target_link_libraries(random_pcl_publisher ${catkin_LIBRARIES}) add_executable(pcl_displayer src/pcl_displayer.cpp) target_link_libraries(pcl_displayer ${catkin_LIBRARIES}) +add_library(curses src/curses.cpp src/curses.h) + +add_executable(keyboard_cmd src/keyboard_cmd.cpp) +target_link_libraries(keyboard_cmd ${catkin_LIBRARIES} ${ncurses_LIBRARIES} curses) + add_executable(normal_estimator src/normal_estimator.cpp) target_link_libraries(normal_estimator ${catkin_LIBRARIES}) add_dependencies(normal_estimator hand_control_generate_messages_cpp) diff --git a/src/curses.cpp b/src/curses.cpp new file mode 100644 index 0000000..62f506f --- /dev/null +++ b/src/curses.cpp @@ -0,0 +1,37 @@ +#include "curses.h" +#include + +const int Curses::kbd_lines = 12; +const int Curses::kbd_columns = 50; +const int Curses::speed_lines = 4; +const int Curses::speed_columns = 50; + +Curses::Curses() { + initscr(); + cbreak(); + noecho(); + kbd = newwin(kbd_lines, kbd_columns, 0, 0); + kbd = newwin(speed_lines, speed_columns, + kbd_lines+1, 0); +} + +Curses::~Curses() { + delwin(kbd); + delwin(speed); + endwin(); +} + +void Curses::print_kbd() { + wmove(kbd, 0, 0); waddstr(kbd, " ---------------------"); + wmove(kbd, 1, 0); waddstr(kbd, "takeoff>| t|⇑ y|↖ u|↑ i|↗ o|"); + wmove(kbd, 2, 0); waddstr(kbd, " |---|---|---|---|---|----"); + wmove(kbd, 3, 0); waddstr(kbd, " reset>| g|⇐ h|← j| k|→ l|⇒ m|"); + wmove(kbd, 4, 0); waddstr(kbd, " |---|---|---|---|---|----"); + wmove(kbd, 5, 0); waddstr(kbd, " land>| b|⇓ n|↙ ,|↓ ;|↘ :|"); + wmove(kbd, 6, 0); waddstr(kbd, " ---------------------"); + wmove(kbd, 8, 0); waddstr(kbd, "a/w : increase/decrease linear `x` speeds by 10%"); + wmove(kbd, 9, 0); waddstr(kbd, "z/x : increase/decrease linear `y` speed by 10%"); + wmove(kbd, 10, 0); waddstr(kbd, "e/c : increase/decrease linear `z` speed by 10%"); + wmove(kbd, 11, 0); waddstr(kbd, "r/v : increase/decrease rotation speed by 10%"); + wrefresh(kbd); +} diff --git a/src/curses.h b/src/curses.h new file mode 100644 index 0000000..559ce16 --- /dev/null +++ b/src/curses.h @@ -0,0 +1,23 @@ +#ifndef CURSES +#define CURSES + +#include + +class Curses +{ + private: + static const int kbd_lines; + static const int kbd_columns; + WINDOW* kbd; + static const char** kbd_descr; + static const int speed_lines; + static const int speed_columns; + WINDOW* speed; + + public: + Curses(); + ~Curses(); + void print_kbd(); +}; + +#endif diff --git a/src/keyboard_cmd.cpp b/src/keyboard_cmd.cpp index ac52ac1..577ceb9 100644 --- a/src/keyboard_cmd.cpp +++ b/src/keyboard_cmd.cpp @@ -6,7 +6,7 @@ #include #include -#include +#include "curses.h" #include #include @@ -25,17 +25,14 @@ class Run void reset() { pub_reset.publish(empty); }; float x_speed, y_speed, z_speed, turn; - void print_speed() - { - std::cout << "x speed : " << x_speed << ", y speed : " << - y_speed << ", z speed : " << z_speed << - ", rotation speed : " << turn << "\n"; - }; + Curses term; + void print_speed() { ; }; public: Run() : n(), empty(), + term(), loop_rate(30), x_speed(0.2), y_speed(0.3), @@ -47,11 +44,6 @@ class Run pub_reset = n.advertise("/ardrone/reset", 1); } - ~Run() - { - endwin(); - } - void operator()() { @@ -71,10 +63,6 @@ class Run <<"r/v : increase/decrease rotation speed by 10%\n"; */ - initscr(); - cbreak(); - noecho(); - while (ros::ok()) { geometry_msgs::Twist::Ptr msg(new geometry_msgs::Twist()); @@ -232,12 +220,11 @@ class Run default : break; } // switch - ros::spinOnce(); loop_rate.sleep(); - } // while } // run + }; // class int main(int argc, char** argv) diff --git a/src/test.cpp b/src/test.cpp new file mode 100644 index 0000000..9c75f61 --- /dev/null +++ b/src/test.cpp @@ -0,0 +1,8 @@ +#include "curses.h" +int main() +{ +Curses term; +term.print_kbd(); +for(;;) ; +} +