Go to the documentation of this file.00001
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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 { };
00071 }
00072
00073 private:
00074 UAS *uas;
00075
00076 ros::NodeHandle sp_nh;
00077 ros::Subscriber vision_vel_sub;
00078
00079
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
00091
00095 void send_vision_speed(float vx, float vy, float vz, const ros::Time &stamp) {
00096
00097
00098 vision_speed_estimate(stamp.toNSec() / 1000,
00099 vy, vx, -vz);
00100 }
00101
00102
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 };
00114
00115 PLUGINLIB_EXPORT_CLASS(mavplugin::VisionSpeedEstimatePlugin, mavplugin::MavRosPlugin)