on progress

This commit is contained in:
Louis-Guillaume DUBOIS 2015-05-02 15:37:58 +02:00
parent 2e325bbf96
commit df80fbfcb8
3 changed files with 94 additions and 56 deletions

View file

@ -1,46 +1,70 @@
#include <ncurses.h>
#include <string>
#include "display.h"
const int Curses::kbd_lines = 12;
const int Curses::kbd_columns = 50;
const int Curses::speed_lines = 4;
const int Curses::speed_columns = 50;
const int Curses::cmd_kbd_lines = 12;
const int Curses::cmd_kbd_columns = 50;
const int Curses::cmd_speed_lines = 4;
const int Curses::cmd_speed_columns = 50;
Curses::Curses() {
initscr();
cbreak();
//noecho();
kbd = newwin(kbd_lines, kbd_columns, 0, 0);
speed = newwin(speed_lines, speed_columns, kbd_lines+1, 0);
get = newwin(1,1,kbd_lines+speed_lines+1,2);
print_kbd();
cmd_kbd = newwin(cmd_kbd_lines, cmd_kbd_columns, 0, 0);
cmd_speed = newwin(cmd_speed_lines,
cmd_speed_columns, cmd_kbd_lines+1, 0);
get = newwin(1,1,cmd_kbd_lines + cmd_speed_lines + 1,2);
//log_sent_w = newwin(///
//nav_data = newwin(//
print_cmd_kbd();
print_cmd_speed();
wmove(get, 0, 0);
wrefresh(get);
}
Curses::~Curses() {
delwin(kbd);
delwin(speed);
delwin(cmd_kbd);
delwin(cmd_speed);
delwin(log_sent_w);
delwin(nav_data);
delwin(get);
endwin();
}
char Curses::getchar()
{
char Curses::getchar() {
return wgetch(get);
}
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);
void Curses::print_cmd_kbd() {
wmove(cmd_kbd, 0, 0); waddstr(cmd_kbd, " ---------------------");
wmove(cmd_kbd, 1, 0); waddstr(cmd_kbd, "takeoff>| t|⇑ y|↖ u|↑ i|↗ o|");
wmove(cmd_kbd, 2, 0); waddstr(cmd_kbd, " |---|---|---|---|---|----");
wmove(cmd_kbd, 3, 0); waddstr(cmd_kbd, " reset>| g|⇐ h|← j| k|→ l|⇒ m|");
wmove(cmd_kbd, 4, 0); waddstr(cmd_kbd, " |---|---|---|---|---|----");
wmove(cmd_kbd, 5, 0); waddstr(cmd_kbd, " land>| b|⇓ n|↙ ,|↓ ;|↘ :|");
wmove(cmd_kbd, 6, 0); waddstr(cmd_kbd, " ---------------------");
wmove(cmd_kbd, 8, 0); waddstr(cmd_kbd, "a/w : increase/decrease linear `x` speeds by 10%");
wmove(cmd_kbd, 9, 0); waddstr(cmd_kbd, "z/x : increase/decrease linear `y` speed by 10%");
wmove(cmd_kbd, 10, 0); waddstr(cmd_kbd, "e/c : increase/decrease linear `z` speed by 10%");
wmove(cmd_kbd, 11, 0); waddstr(cmd_kbd, "r/v : increase/decrease rotation speed by 10%");
wrefresh(cmd_kbd);
}
void Curses::print_cmd_speed() {
}
void Curses::update_cmd_speed(const char& coord, const float& v) {
}
void Curses::log_sent(const std::string& str) {
}
void Curses::update_navdata(const float& batteryPercent,
const int& state,
const float& time) {
}

View file

@ -2,17 +2,19 @@
#define CURSES_DISPLAY
#include <ncurses.h>
#include <string>
class Curses
{
private:
static const int kbd_lines;
static const int kbd_columns;
WINDOW* kbd;
static const int speed_lines;
static const int speed_columns;
WINDOW* speed;
void print_kbd();
static const int cmd_kbd_lines;
static const int cmd_kbd_columns;
WINDOW* cmd_kbd;
static const int cmd_speed_lines;
static const int cmd_speed_columns;
WINDOW* cmd_speed;
void print_cmd_kbd();
void print_cmd_speed();
WINDOW* get;
// TODO (avec scroll)
@ -25,9 +27,11 @@ class Curses
char getchar();
// TODO
void update_speed(const char&, const float&);
// void update_navdata(...
void log_sent(char*);
void update_cmd_speed(const char& coord, const float& v);
void update_navdata(const float& batteryPercent,
const int& state,
const float& time);
void log_sent(const std::string& str);
};
#endif

View file

@ -6,6 +6,21 @@
#include <std_msgs/Empty.h>
#include <geometry_msgs/Twist.h>
#include <ardrone_autonomy/Navdata.h>
class Callback
{
private:
boost::shared_ptr<Curses> term;
public:
Callback(const boost::shared_ptr<Curses>& terminal) :
term(terminal) {}
void operator()(const ardrone_autonomy::Navdata::ConstPtr msg) {
term->update_navdata(msg->batteryPercent, msg->state, msg->tm);
}
}; // class Callback
class Run
{
@ -14,17 +29,17 @@ class Run
ros::NodeHandle n;
ros::Rate loop_rate;
ros::Publisher cmd, pub_takeoff, pub_land, pub_reset;
void land()
{ pub_land.publish(empty); };
void takeoff()
{ pub_takeoff.publish(empty); };
void reset()
{ pub_reset.publish(empty); };
ros::Subscriber data_subscriber;
void land() { pub_land.publish(empty); };
void takeoff() { pub_takeoff.publish(empty); };
void reset() { pub_reset.publish(empty); };
float x_speed, y_speed, z_speed, turn;
boost::shared_ptr<Curses> term;
Callback data_callback;
public:
Run(boost::shared_ptr<Curses> terminal) :
Run(const boost::shared_ptr<Curses>& terminal) :
data_callback(terminal),
term(terminal),
loop_rate(30),
x_speed(0.2),
@ -35,6 +50,7 @@ class Run
pub_takeoff = n.advertise<std_msgs::Empty>("/ardrone/takeoff", 1);
pub_land = n.advertise<std_msgs::Empty>("/ardrone/land", 1);
pub_reset = n.advertise<std_msgs::Empty>("/ardrone/reset", 1);
data_subscriber = n.subscribe<ardrone_autonomy::Navdata>("/ardrone/navdata", 1, data_callback);
}
void operator()()
@ -166,49 +182,49 @@ class Run
case 'a' :
{// + x_speed
x_speed *= 1.1;
term->update_speed('x', x_speed);
term->update_cmd_speed('x', x_speed);
break;
}
case 'w' :
{// - x_speed
x_speed *= 0.9;
term->update_speed('x', x_speed);
term->update_cmd_speed('x', x_speed);
break;
}
case 'z' :
{// + y_speed
y_speed *= 1.1;
term->update_speed('y', y_speed);
term->update_cmd_speed('y', y_speed);
break;
}
case 'x' :
{// - y_speed
y_speed *= 0.9;
term->update_speed('y', y_speed);
term->update_cmd_speed('y', y_speed);
break;
}
case 'e' :
{// + z_speed
z_speed *= 1.1;
term->update_speed('z', z_speed);
term->update_cmd_speed('z', z_speed);
break;
}
case 'c' :
{// - z_speed
z_speed *= 0.9;
term->update_speed('z', z_speed);
term->update_cmd_speed('z', z_speed);
break;
}
case 'r' :
{// + turn speed
turn *= 1.1;
term->update_speed('t', turn);
term->update_cmd_speed('t', turn);
break;
}
case 'v' :
{// - turn speed
turn *= 0.9;
term->update_speed('t', turn);
term->update_cmd_speed('t', turn);
break;
}
default :
@ -220,12 +236,6 @@ class Run
}; // class Run
class Callback
{
//TODO
// receives nav_data and display them in the term
}; // class Callback
int main(int argc, char** argv)
{
setlocale(LC_ALL, "");