2015-08-21 18:39:01 +00:00
|
|
|
/* Copyright (C) 2015 CentraleSupélec
|
|
|
|
* All rights reserved
|
|
|
|
*/
|
2015-05-27 14:52:09 +00:00
|
|
|
#include <ros/ros.h>
|
|
|
|
#include <ros/time.h>
|
|
|
|
#include <locale.h>
|
|
|
|
#include <limits>
|
|
|
|
#include <math.h>
|
|
|
|
#include <assert.h>
|
|
|
|
|
|
|
|
#include <pcl_ros/point_cloud.h>
|
|
|
|
#include <pcl/point_types.h>
|
|
|
|
|
|
|
|
#include <hand_control/Plan.h>
|
|
|
|
#include <geometry_msgs/Twist.h>
|
|
|
|
#include <math.h>
|
|
|
|
|
|
|
|
#include <dynamic_reconfigure/server.h>
|
2015-05-27 20:27:57 +00:00
|
|
|
#include <hand_control/CommanderConfig.h>
|
2015-05-27 14:52:09 +00:00
|
|
|
|
|
|
|
|
|
|
|
class Run
|
|
|
|
{
|
|
|
|
private:
|
2015-06-26 18:13:29 +00:00
|
|
|
float xx, yy, zz, theta; // read coords
|
2015-05-27 14:52:09 +00:00
|
|
|
|
2015-06-26 18:13:29 +00:00
|
|
|
// see README.md to know what are the parameters
|
|
|
|
float x_vel, y_vel, z_vel, angle_vel, up_factor, neutral_z; // parameters
|
|
|
|
float max_curv; // not used yet
|
|
|
|
float z_dev_min, x_dev_min, y_dev_min, th_dev_min; // parameters : thresholds
|
|
|
|
uint64_t min_number; // parameter
|
|
|
|
bool no_diag; // parameter
|
2015-05-27 14:52:09 +00:00
|
|
|
|
|
|
|
ros::Publisher pub;
|
|
|
|
|
|
|
|
void publish()
|
2015-06-26 18:13:29 +00:00
|
|
|
// build and publish a message from the "xx", "yy", "zz" and "theta" informations
|
2015-05-27 14:52:09 +00:00
|
|
|
{
|
|
|
|
geometry_msgs::Twist::Ptr mvt(new geometry_msgs::Twist());
|
|
|
|
|
|
|
|
if (fabs(zz) > z_dev_min)
|
|
|
|
{
|
2015-06-26 18:13:29 +00:00
|
|
|
// up_factor to balance out the gravity effect
|
2015-05-27 14:52:09 +00:00
|
|
|
if (zz > 0)
|
|
|
|
mvt->linear.z = zz * z_vel * up_factor ;
|
|
|
|
else
|
|
|
|
mvt->linear.z = zz * z_vel;
|
|
|
|
}
|
2015-06-26 18:13:29 +00:00
|
|
|
|
|
|
|
|
|
|
|
// no_diag true : the drone can only translate on the "x" axis
|
|
|
|
// or the "y" axis but not on a linear combination of these axes.
|
2015-06-09 15:00:45 +00:00
|
|
|
if (no_diag)
|
2015-05-27 14:52:09 +00:00
|
|
|
{
|
2015-06-09 15:00:45 +00:00
|
|
|
if (fabs(yy) > fabs(xx) && fabs(yy) > y_dev_min)
|
|
|
|
{
|
|
|
|
mvt->linear.y = yy * y_vel;
|
|
|
|
}
|
|
|
|
else if (fabs(xx) > x_dev_min)
|
|
|
|
{
|
|
|
|
mvt->linear.x = - xx * x_vel;
|
|
|
|
}
|
2015-06-26 18:13:29 +00:00
|
|
|
} else // no_diag false : the drone can translate on any possible direction
|
2015-05-27 14:52:09 +00:00
|
|
|
{
|
2015-06-09 15:00:45 +00:00
|
|
|
if (fabs(yy) > y_dev_min)
|
|
|
|
mvt->linear.y = yy * y_vel;
|
|
|
|
if (fabs(xx) > x_dev_min)
|
|
|
|
mvt->linear.x = - xx * x_vel;
|
2015-05-27 14:52:09 +00:00
|
|
|
}
|
2015-05-27 21:28:43 +00:00
|
|
|
|
|
|
|
if (fabs(theta) > th_dev_min) {
|
|
|
|
mvt->angular.z = theta * angle_vel;
|
|
|
|
}
|
2015-05-27 14:52:09 +00:00
|
|
|
|
|
|
|
pub.publish(mvt);
|
|
|
|
ROS_INFO("cmd published");
|
2015-06-26 18:13:29 +00:00
|
|
|
}
|
2015-05-27 14:52:09 +00:00
|
|
|
|
|
|
|
public:
|
2015-05-27 17:48:06 +00:00
|
|
|
Run(const ros::Publisher& cmd_publisher) :
|
2015-06-26 18:13:29 +00:00
|
|
|
pub(cmd_publisher) {}
|
2015-05-27 14:52:09 +00:00
|
|
|
|
|
|
|
void callback(const hand_control::Plan::ConstPtr& msg)
|
2015-06-26 18:13:29 +00:00
|
|
|
// handle received messages
|
2015-05-27 14:52:09 +00:00
|
|
|
{
|
|
|
|
ROS_INFO("plan received");
|
|
|
|
if (msg->curvature < max_curv && msg->number > min_number)
|
2015-06-26 18:13:29 +00:00
|
|
|
// we ever have msg->curvature == 0 in fact (not implemented yet)
|
2015-05-27 14:52:09 +00:00
|
|
|
{
|
2015-05-27 21:28:43 +00:00
|
|
|
|
2015-05-27 14:52:09 +00:00
|
|
|
if(msg->normal.z > 0)
|
|
|
|
{
|
|
|
|
yy = msg->normal.x;
|
|
|
|
xx = msg->normal.y;
|
|
|
|
}
|
|
|
|
else
|
|
|
|
{
|
|
|
|
yy = - msg->normal.x;
|
|
|
|
xx = - msg->normal.y;
|
|
|
|
}
|
|
|
|
|
|
|
|
zz = msg->altitude - neutral_z;
|
|
|
|
|
2015-05-27 21:28:43 +00:00
|
|
|
theta = msg->angle;
|
|
|
|
// theta between -90 and 90
|
2015-05-27 14:52:09 +00:00
|
|
|
|
|
|
|
ROS_INFO("coords updated");
|
|
|
|
} else {
|
|
|
|
xx = yy = zz = 0.;
|
|
|
|
}
|
|
|
|
publish();
|
|
|
|
};
|
|
|
|
|
2015-06-26 18:13:29 +00:00
|
|
|
void reconfigure(const hand_control::CommanderConfig& c, const uint32_t& level)
|
|
|
|
// updates the parameters (received with dynamic_reconfigure)
|
|
|
|
{
|
2015-05-27 14:52:09 +00:00
|
|
|
max_curv = c.max_curvature;
|
|
|
|
x_dev_min = c.x_minimal_deviation;
|
|
|
|
y_dev_min = c.y_minimal_deviation;
|
|
|
|
z_dev_min = c.z_minimal_deviation;
|
|
|
|
th_dev_min = c.theta_minimal_deviation;
|
|
|
|
neutral_z = c.neutral_alt;
|
|
|
|
min_number = c.min_points_number;
|
|
|
|
up_factor = c.up_fact;
|
2015-06-03 17:19:15 +00:00
|
|
|
x_vel = c.x_vel;
|
|
|
|
y_vel = c.y_vel;
|
2015-05-27 18:10:33 +00:00
|
|
|
z_vel = c.z_vel;
|
|
|
|
angle_vel = c.angle_vel;
|
2015-06-09 15:00:45 +00:00
|
|
|
no_diag = c.no_diag;
|
2015-05-27 14:52:09 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
void run()
|
2015-06-26 18:13:29 +00:00
|
|
|
// runs the callbacks and publications process
|
2015-05-27 14:52:09 +00:00
|
|
|
{
|
2015-05-27 21:28:43 +00:00
|
|
|
ros::spin();
|
2015-05-27 14:52:09 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
};
|
|
|
|
|
|
|
|
int main(int argc, char** argv)
|
|
|
|
{
|
2015-05-27 20:27:57 +00:00
|
|
|
ros::init(argc, argv, "commander");
|
|
|
|
ros::NodeHandle node("commander");
|
2015-05-27 14:52:09 +00:00
|
|
|
ros::Publisher cmd_pub = node.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
|
2015-05-27 17:48:06 +00:00
|
|
|
Run run(cmd_pub);
|
2015-05-27 14:52:09 +00:00
|
|
|
ros::Subscriber plan_sub = node.subscribe<hand_control::Plan>("input", 1, &Run::callback, &run);
|
2015-05-27 21:28:43 +00:00
|
|
|
|
2015-06-26 18:13:29 +00:00
|
|
|
// setting up dynamic_reconfigure (for rqt_reconfigure)
|
2015-05-27 20:27:57 +00:00
|
|
|
dynamic_reconfigure::Server<hand_control::CommanderConfig> server;
|
|
|
|
dynamic_reconfigure::Server<hand_control::CommanderConfig>::CallbackType f;
|
2015-05-27 14:52:09 +00:00
|
|
|
f = boost::bind(&Run::reconfigure, &run, _1, _2);
|
|
|
|
server.setCallback(f);
|
|
|
|
|
2015-06-26 18:13:29 +00:00
|
|
|
// starts working
|
2015-05-27 14:52:09 +00:00
|
|
|
run.run();
|
|
|
|
return 0;
|
|
|
|
}
|