22 #include <geometry_msgs/TwistStamped.h> 23 #include <geometry_msgs/Twist.h> 25 #include <mavros_msgs/SetMavFrame.h> 28 namespace std_plugins {
29 using mavlink::common::MAV_FRAME;
39 sp_nh(
"~setpoint_velocity")
44 PluginBase::initialize(uas_);
52 std::string mav_frame_str;
88 uint16_t ignore_all_except_v_xyz_yr = (1 << 10) | (7 << 6) | (7 << 0);
90 if (mav_frame == MAV_FRAME::BODY_NED || mav_frame == MAV_FRAME::BODY_OFFSET_NED) {
98 if (mav_frame == MAV_FRAME::BODY_NED || mav_frame == MAV_FRAME::BODY_OFFSET_NED) {
107 ignore_all_except_v_xyz_yr,
108 Eigen::Vector3d::Zero(),
110 Eigen::Vector3d::Zero(),
117 Eigen::Vector3d vel_enu;
121 req->twist.angular.z);
125 Eigen::Vector3d vel_enu;
132 bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
134 mav_frame =
static_cast<MAV_FRAME>(req.mav_frame);
136 sp_nh.
setParam(
"mav_frame", mav_frame_str);
MAVROS Plugin base class.
std::shared_ptr< MAVConnInterface const > ConstPtr
void vel_unstamped_cb(const geometry_msgs::Twist::ConstPtr &req)
mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
Retreive MAV_FRAME from name.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void set_position_target_local_ned(uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, Eigen::Vector3d p, Eigen::Vector3d v, Eigen::Vector3d af, float yaw, float yaw_rate)
Message specification: https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED.
PluginBase()
Plugin constructor Should not do anything before initialize()
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
ros::Subscriber vel_unstamped_sub
Setpoint velocity plugin.
void initialize(UAS &uas_)
Plugin initializer.
Mixin for setpoint plugins.
bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
std::string to_string(timesync_mode e)
T transform_frame_ned_enu(const T &in)
Transform data expressed in NED to ENU frame.
T transform_frame_baselink_aircraft(const T &in)
Transform data expressed in Baselink frame to Aircraft frame.
friend class SetPositionTargetLocalNEDMixin
T transform_frame_enu_ned(const T &in)
Transform data expressed in ENU to NED frame.
void send_setpoint_velocity(const ros::Time &stamp, Eigen::Vector3d &vel_enu, double yaw_rate)
Send velocity to FCU velocity controller.
This mixin adds set_position_target_local_ned()
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
bool getParam(const std::string &key, std::string &s) const
void vel_cb(const geometry_msgs::TwistStamped::ConstPtr &req)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ros::ServiceServer mav_frame_srv
constexpr std::underlying_type< _T >::type enum_value(_T e)