2015-05-01 17:38:54 +00:00
|
|
|
|
#include <ros/ros.h>
|
|
|
|
|
#include <ros/time.h>
|
2015-05-01 21:22:13 +00:00
|
|
|
|
#include <locale.h>
|
|
|
|
|
#include <ncurses.h>
|
|
|
|
|
#include "display.h"
|
2015-05-01 17:38:54 +00:00
|
|
|
|
|
|
|
|
|
#include <std_msgs/Empty.h>
|
|
|
|
|
#include <geometry_msgs/Twist.h>
|
2015-05-02 13:37:58 +00:00
|
|
|
|
#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
|
2015-05-01 17:38:54 +00:00
|
|
|
|
|
|
|
|
|
class Run
|
|
|
|
|
{
|
|
|
|
|
private:
|
|
|
|
|
std_msgs::Empty empty;
|
|
|
|
|
ros::NodeHandle n;
|
|
|
|
|
ros::Rate loop_rate;
|
|
|
|
|
ros::Publisher cmd, pub_takeoff, pub_land, pub_reset;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
ros::Subscriber data_subscriber;
|
|
|
|
|
void land() { pub_land.publish(empty); };
|
|
|
|
|
void takeoff() { pub_takeoff.publish(empty); };
|
|
|
|
|
void reset() { pub_reset.publish(empty); };
|
2015-05-01 17:38:54 +00:00
|
|
|
|
float x_speed, y_speed, z_speed, turn;
|
2015-05-01 22:00:28 +00:00
|
|
|
|
boost::shared_ptr<Curses> term;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
Callback data_callback;
|
2015-05-01 17:38:54 +00:00
|
|
|
|
|
|
|
|
|
public:
|
2015-05-02 13:37:58 +00:00
|
|
|
|
Run(const boost::shared_ptr<Curses>& terminal) :
|
|
|
|
|
data_callback(terminal),
|
2015-05-01 22:00:28 +00:00
|
|
|
|
term(terminal),
|
2015-05-01 17:38:54 +00:00
|
|
|
|
loop_rate(30),
|
|
|
|
|
x_speed(0.2),
|
|
|
|
|
y_speed(0.3),
|
|
|
|
|
z_speed(0.5),
|
|
|
|
|
turn(0.5) {
|
|
|
|
|
cmd = n.advertise<geometry_msgs::Twist>("/cmd_vel",1);
|
|
|
|
|
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);
|
2015-05-02 13:37:58 +00:00
|
|
|
|
data_subscriber = n.subscribe<ardrone_autonomy::Navdata>("/ardrone/navdata", 1, data_callback);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void operator()()
|
|
|
|
|
{
|
|
|
|
|
while (ros::ok())
|
|
|
|
|
{
|
2015-05-01 22:40:28 +00:00
|
|
|
|
ros::spinOnce();
|
|
|
|
|
|
2015-05-01 17:38:54 +00:00
|
|
|
|
geometry_msgs::Twist::Ptr msg(new geometry_msgs::Twist());
|
|
|
|
|
msg->linear.x = msg->linear.y = msg->linear.z =
|
|
|
|
|
msg->angular.x = msg->angular.y = msg->angular.z = 0.;
|
|
|
|
|
|
2015-05-01 22:00:28 +00:00
|
|
|
|
char c = term->getchar();
|
2015-05-01 17:38:54 +00:00
|
|
|
|
|
|
|
|
|
switch(c)
|
|
|
|
|
{
|
|
|
|
|
case 'k' :
|
|
|
|
|
{// hover
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("hover !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'i' :
|
|
|
|
|
{// forward
|
|
|
|
|
msg->linear.x = x_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("forward !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case ';' :
|
|
|
|
|
{// backward
|
|
|
|
|
msg->linear.x = -x_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("backward !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'h' :
|
|
|
|
|
{//translate left
|
|
|
|
|
msg->linear.y = -y_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("translate left !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'm' :
|
|
|
|
|
{//translate right
|
|
|
|
|
msg->linear.y = y_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("translate right !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'j' :
|
|
|
|
|
{//rotate left
|
|
|
|
|
msg->angular.z = turn;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("rotate left !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'l' :
|
|
|
|
|
{//rotate right
|
|
|
|
|
msg->angular.z = -turn;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("rotate right !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'u' :
|
|
|
|
|
{//turn left
|
|
|
|
|
msg->angular.z = turn;
|
|
|
|
|
msg->linear.x = x_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("forward left !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'o' :
|
|
|
|
|
{//turn right
|
|
|
|
|
msg->angular.z = -turn;
|
|
|
|
|
msg->linear.x = x_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("forward right !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case ',' :
|
|
|
|
|
{//turn left backward
|
|
|
|
|
msg->angular.z = turn;
|
|
|
|
|
msg->linear.x = -x_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("backward left !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case ':' :
|
|
|
|
|
{//turn right backward
|
|
|
|
|
msg->angular.z = -turn;
|
|
|
|
|
msg->linear.x = -x_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("backward right !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'y' :
|
|
|
|
|
{//up
|
|
|
|
|
msg->linear.z = z_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("up !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'n' :
|
|
|
|
|
{//down
|
|
|
|
|
msg->linear.z = -z_speed;
|
|
|
|
|
cmd.publish(msg);
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("down !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 't' :
|
|
|
|
|
{//takeoff
|
|
|
|
|
takeoff();
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("takeoff !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'b' :
|
|
|
|
|
{//land
|
|
|
|
|
land();
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("land !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'g' :
|
|
|
|
|
{//reset
|
|
|
|
|
reset();
|
2015-05-01 22:40:28 +00:00
|
|
|
|
term->log_sent("reset !");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'a' :
|
|
|
|
|
{// + x_speed
|
|
|
|
|
x_speed *= 1.1;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
term->update_cmd_speed('x', x_speed);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'w' :
|
|
|
|
|
{// - x_speed
|
|
|
|
|
x_speed *= 0.9;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
term->update_cmd_speed('x', x_speed);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'z' :
|
|
|
|
|
{// + y_speed
|
|
|
|
|
y_speed *= 1.1;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
term->update_cmd_speed('y', y_speed);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'x' :
|
|
|
|
|
{// - y_speed
|
|
|
|
|
y_speed *= 0.9;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
term->update_cmd_speed('y', y_speed);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'e' :
|
|
|
|
|
{// + z_speed
|
|
|
|
|
z_speed *= 1.1;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
term->update_cmd_speed('z', z_speed);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'c' :
|
|
|
|
|
{// - z_speed
|
|
|
|
|
z_speed *= 0.9;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
term->update_cmd_speed('z', z_speed);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'r' :
|
|
|
|
|
{// + turn speed
|
|
|
|
|
turn *= 1.1;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
term->update_cmd_speed('t', turn);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
case 'v' :
|
|
|
|
|
{// - turn speed
|
|
|
|
|
turn *= 0.9;
|
2015-05-02 13:37:58 +00:00
|
|
|
|
term->update_cmd_speed('t', turn);
|
2015-05-01 17:38:54 +00:00
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
default :
|
|
|
|
|
break;
|
2015-05-01 22:40:28 +00:00
|
|
|
|
} // switch(c)
|
2015-05-01 17:38:54 +00:00
|
|
|
|
loop_rate.sleep();
|
|
|
|
|
} // while
|
2015-05-01 22:40:28 +00:00
|
|
|
|
} //void run()
|
2015-05-01 19:23:00 +00:00
|
|
|
|
|
2015-05-01 22:40:28 +00:00
|
|
|
|
}; // class Run
|
|
|
|
|
|
2015-05-01 17:38:54 +00:00
|
|
|
|
int main(int argc, char** argv)
|
|
|
|
|
{
|
2015-05-01 21:22:13 +00:00
|
|
|
|
setlocale(LC_ALL, "");
|
2015-05-01 17:38:54 +00:00
|
|
|
|
ros::init(argc, argv, "keyboard_cmd");
|
2015-05-01 22:40:28 +00:00
|
|
|
|
//ros::Subscriber ... (navdata)
|
2015-05-01 22:00:28 +00:00
|
|
|
|
boost::shared_ptr<Curses> term(new Curses());
|
|
|
|
|
Run fun(term);
|
|
|
|
|
fun();
|
2015-05-01 17:38:54 +00:00
|
|
|
|
return 0;
|
2015-05-01 22:40:28 +00:00
|
|
|
|
} // main
|
2015-05-01 17:38:54 +00:00
|
|
|
|
|