vision_speed_estimate.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 <pluginlib/class_list_macros.h>
00030 
00031 #include <geometry_msgs/TwistStamped.h>
00032 #include <geometry_msgs/Vector3Stamped.h>
00033 
00034 namespace mavplugin {
00035 
00043 class VisionSpeedEstimatePlugin : public MavRosPlugin {
00044 public:
00045         VisionSpeedEstimatePlugin() :
00046                 uas(nullptr)
00047         { };
00048 
00049         void initialize(UAS &uas_,
00050                         ros::NodeHandle &nh,
00051                         diagnostic_updater::Updater &diag_updater)
00052         {
00053                 bool listen_twist;
00054                 uas = &uas_;
00055                 sp_nh = ros::NodeHandle(nh, "vision_speed");
00056 
00057                 sp_nh.param("listen_twist", listen_twist, false);
00058 
00059                 if(listen_twist)
00060                         vision_vel_sub = sp_nh.subscribe("speed_twist", 10, &VisionSpeedEstimatePlugin::vel_twist_cb, this);
00061                 else
00062                         vision_vel_sub = sp_nh.subscribe("speed_vector", 10, &VisionSpeedEstimatePlugin::vel_speed_cb, this);
00063         }
00064 
00065         const std::string get_name() const {
00066                 return "VisionSpeedEstimate";
00067         }
00068 
00069         const message_map get_rx_handlers() {
00070                 return { /* Rx disabled */ };
00071         }
00072 
00073 private:
00074         UAS *uas;
00075 
00076         ros::NodeHandle sp_nh;
00077         ros::Subscriber vision_vel_sub;
00078 
00079         /* -*- low-level send -*- */
00080 
00081         void vision_speed_estimate(uint64_t usec,
00082                         float x, float y, float z) {
00083                 mavlink_message_t msg;
00084                 mavlink_msg_vision_speed_estimate_pack_chan(UAS_PACK_CHAN(uas), &msg,
00085                                 usec,
00086                                 x, y, z);
00087                 UAS_FCU(uas)->send_message(&msg);
00088         }
00089 
00090         /* -*- mid-level helpers -*- */
00091 
00095         void send_vision_speed(float vx, float vy, float vz, const ros::Time &stamp) {
00096 
00097                 // TODO: check conversion. Issue #49.
00098                 vision_speed_estimate(stamp.toNSec() / 1000,
00099                                 vy, vx, -vz);
00100         }
00101 
00102         /* -*- callbacks -*- */
00103 
00104         void vel_twist_cb(const geometry_msgs::TwistStamped::ConstPtr &req) {
00105                 send_vision_speed(req->twist.linear.x, req->twist.linear.y, req->twist.linear.z, req->header.stamp);
00106         }
00107 
00108         void vel_speed_cb(const geometry_msgs::Vector3Stamped::ConstPtr &req) {
00109                 send_vision_speed(req->vector.x, req->vector.y, req->vector.z, req->header.stamp);
00110         }
00111 };
00112 
00113 }; // namespace mavplugin
00114 
00115 PLUGINLIB_EXPORT_CLASS(mavplugin::VisionSpeedEstimatePlugin, mavplugin::MavRosPlugin)


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Wed Aug 26 2015 12:29:20