setpoint_velocity.cpp
Go to the documentation of this file.
00001 
00010 /*
00011  * Copyright 2014 Nuno Marques.
00012  *
00013  * This program is free software; you can redistribute it and/or modify
00014  * it under the terms of the GNU General Public License as published by
00015  * the Free Software Foundation; either version 3 of the License, or
00016  * (at your option) any later version.
00017  *
00018  * This program is distributed in the hope that it will be useful, but
00019  * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
00020  * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
00021  * for more details.
00022  *
00023  * You should have received a copy of the GNU General Public License along
00024  * with this program; if not, write to the Free Software Foundation, Inc.,
00025  * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
00026  */
00027 
00028 #include <mavros/mavros_plugin.h>
00029 #include <mavros/setpoint_mixin.h>
00030 #include <pluginlib/class_list_macros.h>
00031 
00032 #include <geometry_msgs/TwistStamped.h>
00033 
00034 namespace mavplugin {
00035 
00041 class SetpointVelocityPlugin : public MavRosPlugin,
00042         private SetPositionTargetLocalNEDMixin<SetpointVelocityPlugin> {
00043 public:
00044         SetpointVelocityPlugin() :
00045                 uas(nullptr)
00046         { };
00047 
00048         void initialize(UAS &uas_,
00049                         ros::NodeHandle &nh,
00050                         diagnostic_updater::Updater &diag_updater)
00051         {
00052                 uas = &uas_;
00053                 sp_nh = ros::NodeHandle(nh, "setpoint");
00054 
00055                 //cmd_vel usually is the topic used for velocity control in many controllers / planners
00056                 vel_sub = sp_nh.subscribe("cmd_vel", 10, &SetpointVelocityPlugin::vel_cb, this);
00057         }
00058 
00059         const std::string get_name() const {
00060                 return "SetpointVelocity";
00061         }
00062 
00063         const message_map get_rx_handlers() {
00064                 return { /* Rx disabled */ };
00065         }
00066 
00067 private:
00068         friend class SetPositionTargetLocalNEDMixin;
00069         UAS *uas;
00070 
00071         ros::NodeHandle sp_nh;
00072         ros::Subscriber vel_sub;
00073 
00074         /* -*- mid-level helpers -*- */
00075 
00081         void send_setpoint_velocity(const ros::Time &stamp, float vx, float vy, float vz, float yaw_rate) {
00082 
00083                 /* Documentation start from bit 1 instead 0,
00084                  * Ignore position and accel vectors, yaw
00085                  */
00086                 uint16_t ignore_all_except_v_xyz_yr = (1<<10)|(7<<6)|(7<<0);
00087 
00088                 // ENU->NED. Issue #49.
00089                 set_position_target_local_ned(stamp.toNSec() / 1000000,
00090                                 MAV_FRAME_LOCAL_NED,
00091                                 ignore_all_except_v_xyz_yr,
00092                                 0.0, 0.0, 0.0,
00093                                 vy, vx, -vz,
00094                                 0.0, 0.0, 0.0,
00095                                 0.0, yaw_rate);
00096         }
00097 
00098         /* -*- callbacks -*- */
00099 
00100         void vel_cb(const geometry_msgs::TwistStamped::ConstPtr &req) {
00101                 send_setpoint_velocity(req->header.stamp,
00102                                         req->twist.linear.x,
00103                                         req->twist.linear.y,
00104                                         req->twist.linear.z,
00105                                         req->twist.angular.z);
00106         }
00107 };
00108 
00109 }; // namespace mavplugin
00110 
00111 PLUGINLIB_EXPORT_CLASS(mavplugin::SetpointVelocityPlugin, mavplugin::MavRosPlugin)


mavros
Author(s): Vladimir Ermakov
autogenerated on Wed Aug 26 2015 12:29:13