keyboard_cmd on progress

This commit is contained in:
Louis-Guillaume DUBOIS 2015-05-02 00:40:28 +02:00
parent f09c762cb2
commit 6eac98cab3
2 changed files with 48 additions and 22 deletions

View file

@ -1,5 +1,5 @@
#ifndef CURSES_TEST #ifndef CURSES_DISPLAY
#define CURSES_TEST #define CURSES_DISPLAY
#include <ncurses.h> #include <ncurses.h>
@ -9,17 +9,25 @@ class Curses
static const int kbd_lines; static const int kbd_lines;
static const int kbd_columns; static const int kbd_columns;
WINDOW* kbd; WINDOW* kbd;
static const char** kbd_descr;
static const int speed_lines; static const int speed_lines;
static const int speed_columns; static const int speed_columns;
WINDOW* speed; WINDOW* speed;
void print_kbd(); void print_kbd();
WINDOW* get; WINDOW* get;
// TODO (avec scroll)
WINDOW* log_sent_w;
WINDOW* nav_data;
public: public:
Curses(); Curses();
~Curses(); ~Curses();
char getchar(); char getchar();
// TODO
void update_speed(const char&, const float&);
// void update_navdata(...
void log_sent(char*);
}; };
#endif #endif

View file

@ -1,8 +1,3 @@
#include <termios.h>
#include <iostream>
#include <map>
#include <vector>
#include <string>
#include <ros/ros.h> #include <ros/ros.h>
#include <ros/time.h> #include <ros/time.h>
#include <locale.h> #include <locale.h>
@ -27,7 +22,6 @@ class Run
{ pub_reset.publish(empty); }; { pub_reset.publish(empty); };
float x_speed, y_speed, z_speed, turn; float x_speed, y_speed, z_speed, turn;
boost::shared_ptr<Curses> term; boost::shared_ptr<Curses> term;
void print_speed() { ; };
public: public:
Run(boost::shared_ptr<Curses> terminal) : Run(boost::shared_ptr<Curses> terminal) :
@ -47,6 +41,8 @@ class Run
{ {
while (ros::ok()) while (ros::ok())
{ {
ros::spinOnce();
geometry_msgs::Twist::Ptr msg(new geometry_msgs::Twist()); geometry_msgs::Twist::Ptr msg(new geometry_msgs::Twist());
msg->linear.x = msg->linear.y = msg->linear.z = msg->linear.x = msg->linear.y = msg->linear.z =
msg->angular.x = msg->angular.y = msg->angular.z = 0.; msg->angular.x = msg->angular.y = msg->angular.z = 0.;
@ -58,42 +54,49 @@ class Run
case 'k' : case 'k' :
{// hover {// hover
cmd.publish(msg); cmd.publish(msg);
term->log_sent("hover !");
break; break;
} }
case 'i' : case 'i' :
{// forward {// forward
msg->linear.x = x_speed; msg->linear.x = x_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("forward !");
break; break;
} }
case ';' : case ';' :
{// backward {// backward
msg->linear.x = -x_speed; msg->linear.x = -x_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("backward !");
break; break;
} }
case 'h' : case 'h' :
{//translate left {//translate left
msg->linear.y = -y_speed; msg->linear.y = -y_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("translate left !");
break; break;
} }
case 'm' : case 'm' :
{//translate right {//translate right
msg->linear.y = y_speed; msg->linear.y = y_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("translate right !");
break; break;
} }
case 'j' : case 'j' :
{//rotate left {//rotate left
msg->angular.z = turn; msg->angular.z = turn;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("rotate left !");
break; break;
} }
case 'l' : case 'l' :
{//rotate right {//rotate right
msg->angular.z = -turn; msg->angular.z = -turn;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("rotate right !");
break; break;
} }
case 'u' : case 'u' :
@ -101,6 +104,7 @@ class Run
msg->angular.z = turn; msg->angular.z = turn;
msg->linear.x = x_speed; msg->linear.x = x_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("forward left !");
break; break;
} }
case 'o' : case 'o' :
@ -108,6 +112,7 @@ class Run
msg->angular.z = -turn; msg->angular.z = -turn;
msg->linear.x = x_speed; msg->linear.x = x_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("forward right !");
break; break;
} }
case ',' : case ',' :
@ -115,6 +120,7 @@ class Run
msg->angular.z = turn; msg->angular.z = turn;
msg->linear.x = -x_speed; msg->linear.x = -x_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("backward left !");
break; break;
} }
case ':' : case ':' :
@ -122,100 +128,112 @@ class Run
msg->angular.z = -turn; msg->angular.z = -turn;
msg->linear.x = -x_speed; msg->linear.x = -x_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("backward right !");
break; break;
} }
case 'y' : case 'y' :
{//up {//up
msg->linear.z = z_speed; msg->linear.z = z_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("up !");
break; break;
} }
case 'n' : case 'n' :
{//down {//down
msg->linear.z = -z_speed; msg->linear.z = -z_speed;
cmd.publish(msg); cmd.publish(msg);
term->log_sent("down !");
break; break;
} }
case 't' : case 't' :
{//takeoff {//takeoff
takeoff(); takeoff();
term->log_sent("takeoff !");
break; break;
} }
case 'b' : case 'b' :
{//land {//land
land(); land();
term->log_sent("land !");
break; break;
} }
case 'g' : case 'g' :
{//reset {//reset
reset(); reset();
term->log_sent("reset !");
break; break;
} }
case 'a' : case 'a' :
{// + x_speed {// + x_speed
x_speed *= 1.1; x_speed *= 1.1;
print_speed(); term->update_speed('x', x_speed);
break; break;
} }
case 'w' : case 'w' :
{// - x_speed {// - x_speed
x_speed *= 0.9; x_speed *= 0.9;
print_speed(); term->update_speed('x', x_speed);
break; break;
} }
case 'z' : case 'z' :
{// + y_speed {// + y_speed
y_speed *= 1.1; y_speed *= 1.1;
print_speed(); term->update_speed('y', y_speed);
break; break;
} }
case 'x' : case 'x' :
{// - y_speed {// - y_speed
y_speed *= 0.9; y_speed *= 0.9;
print_speed(); term->update_speed('y', y_speed);
break; break;
} }
case 'e' : case 'e' :
{// + z_speed {// + z_speed
z_speed *= 1.1; z_speed *= 1.1;
print_speed(); term->update_speed('z', z_speed);
break; break;
} }
case 'c' : case 'c' :
{// - z_speed {// - z_speed
z_speed *= 0.9; z_speed *= 0.9;
print_speed(); term->update_speed('z', z_speed);
break; break;
} }
case 'r' : case 'r' :
{// + turn speed {// + turn speed
turn *= 1.1; turn *= 1.1;
print_speed(); term->update_speed('t', turn);
break; break;
} }
case 'v' : case 'v' :
{// - turn speed {// - turn speed
turn *= 0.9; turn *= 0.9;
print_speed(); term->update_speed('t', turn);
break; break;
} }
default : default :
break; break;
} // switch } // switch(c)
ros::spinOnce();
loop_rate.sleep(); loop_rate.sleep();
} // while } // while
} // run } //void run()
}; // class }; // class Run
class Callback
{
//TODO
// receives nav_data and display them in the term
}; // class Callback
int main(int argc, char** argv) int main(int argc, char** argv)
{ {
setlocale(LC_ALL, ""); setlocale(LC_ALL, "");
ros::init(argc, argv, "keyboard_cmd"); ros::init(argc, argv, "keyboard_cmd");
//ros::Subscriber ... (navdata)
boost::shared_ptr<Curses> term(new Curses()); boost::shared_ptr<Curses> term(new Curses());
Run fun(term); Run fun(term);
fun(); fun();
return 0; return 0;
} } // main