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/utils.h>
00029 #include <mavros/mavros_plugin.h>
00030 #include <mavros/setpoint_mixin.h>
00031 #include <pluginlib/class_list_macros.h>
00032
00033 #include <geometry_msgs/Vector3Stamped.h>
00034
00035 namespace mavplugin {
00036
00042 class SetpointAccelerationPlugin : public MavRosPlugin,
00043 private SetPositionTargetLocalNEDMixin<SetpointAccelerationPlugin> {
00044 public:
00045 SetpointAccelerationPlugin() :
00046 uas(nullptr),
00047 send_force(false)
00048 { };
00049
00050 void initialize(UAS &uas_,
00051 ros::NodeHandle &nh,
00052 diagnostic_updater::Updater &diag_updater)
00053 {
00054 uas = &uas_;
00055 sp_nh = ros::NodeHandle(nh, "setpoint");
00056
00057 sp_nh.param("accel/send_force", send_force, false);
00058
00059 accel_sub = sp_nh.subscribe("accel", 10, &SetpointAccelerationPlugin::accel_cb, this);
00060 }
00061
00062 const std::string get_name() const {
00063 return "SetpointAcceleration";
00064 }
00065
00066 const message_map get_rx_handlers() {
00067 return { };
00068 }
00069
00070 private:
00071 friend class SetPositionTargetLocalNEDMixin;
00072 UAS *uas;
00073
00074 ros::NodeHandle sp_nh;
00075 ros::Subscriber accel_sub;
00076
00077 bool send_force;
00078
00079
00080
00086 void send_setpoint_acceleration(const ros::Time &stamp, float afx, float afy, float afz) {
00087
00088
00089
00090
00091 uint16_t ignore_all_except_a_xyz = (3<<10)|(7<<3)|(7<<0);
00092
00093 if (send_force)
00094 ignore_all_except_a_xyz |= (1<<9);
00095
00096
00097 set_position_target_local_ned(stamp.toNSec() / 1000000,
00098 MAV_FRAME_LOCAL_NED,
00099 ignore_all_except_a_xyz,
00100 0.0, 0.0, 0.0,
00101 0.0, 0.0, 0.0,
00102 afy, afx, -afz,
00103 0.0, 0.0);
00104 }
00105
00106
00107
00108 void accel_cb(const geometry_msgs::Vector3Stamped::ConstPtr &req) {
00109 send_setpoint_acceleration(req->header.stamp,
00110 req->vector.x,
00111 req->vector.y,
00112 req->vector.z);
00113 }
00114 };
00115
00116 };
00117
00118 PLUGINLIB_EXPORT_CLASS(mavplugin::SetpointAccelerationPlugin, mavplugin::MavRosPlugin)