Go to the documentation of this file.
21 #include <geometry_msgs/PoseStamped.h>
23 #include <mavros_msgs/SetMavFrame.h>
24 #include <geographic_msgs/GeoPoseStamped.h>
26 #include <GeographicLib/Geocentric.hpp>
29 namespace std_plugins {
30 using mavlink::common::MAV_FRAME;
41 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 sp_nh(
"~setpoint_position"),
52 PluginBase::initialize(uas_);
79 std::string mav_frame_str;
129 using mavlink::common::MAV_FRAME;
137 const uint16_t ignore_all_except_xyz_y = (1 << 11) | (7 << 6) | (7 << 3);
140 if (
static_cast<MAV_FRAME
>(
mav_frame) == MAV_FRAME::BODY_NED ||
static_cast<MAV_FRAME
>(
mav_frame) == MAV_FRAME::BODY_OFFSET_NED) {
158 ignore_all_except_xyz_y,
160 Eigen::Vector3d::Zero(),
161 Eigen::Vector3d::Zero(),
191 using mavlink::common::POSITION_TARGET_TYPEMASK;
193 uint16_t type_mask = uint16_t(POSITION_TARGET_TYPEMASK::VX_IGNORE)
194 | uint16_t(POSITION_TARGET_TYPEMASK::VY_IGNORE)
195 | uint16_t(POSITION_TARGET_TYPEMASK::VZ_IGNORE)
196 | uint16_t(POSITION_TARGET_TYPEMASK::AX_IGNORE)
197 | uint16_t(POSITION_TARGET_TYPEMASK::AY_IGNORE)
198 | uint16_t(POSITION_TARGET_TYPEMASK::AZ_IGNORE);
200 Eigen::Quaterniond attitude;
206 req->header.stamp.toNSec() / 1000000,
207 uint8_t(MAV_FRAME::GLOBAL_INT),
209 req->pose.position.latitude * 1e7,
210 req->pose.position.longitude * 1e7,
211 req->pose.position.altitude,
212 Eigen::Vector3d::Zero(),
213 Eigen::Vector3d::Zero(),
231 GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f());
233 Eigen::Vector3d goal_gps(req->pose.position.latitude, req->pose.position.longitude, req->pose.position.altitude);
236 Eigen::Vector3d current_ecef;
238 current_ecef.x(), current_ecef.y(), current_ecef.z());
241 Eigen::Vector3d goal_ecef;
242 earth.Forward(goal_gps.x(), goal_gps.y(), goal_gps.z(),
243 goal_ecef.x(), goal_ecef.y(), goal_ecef.z());
246 Eigen::Vector3d ecef_offset = goal_ecef - current_ecef;
251 Eigen::Quaterniond q;
258 sp.linear() = q.toRotationMatrix();
261 if ((req->header.stamp.toNSec() / 1000000) >
old_gps_stamp) {
286 bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
288 mav_frame =
static_cast<MAV_FRAME
>(req.mav_frame);
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
T transform_frame_baselink_aircraft(const T &in)
Transform data expressed in Baselink frame to Aircraft frame.
T transform_frame_enu_ned(const T &in)
Transform data expressed in ENU to NED frame.
void gps_cb(const sensor_msgs::NavSatFix::ConstPtr &msg)
Setpoint position plugin.
void setParam(const std::string &key, bool b) const
mavlink::common::MAV_FRAME mav_frame_from_str(const std::string &mav_frame)
Retreive MAV_FRAME from name.
ros::Subscriber local_sub
current local ENU
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
This mixin adds TF2 listener thread to plugin.
friend class SetPositionTargetLocalNEDMixin
Eigen::Vector3d current_gps
geodetic coordinates LLA
double quaternion_get_yaw(const Eigen::Quaterniond &q)
Get Yaw angle from quaternion.
void send_position_target(const ros::Time &stamp, const Eigen::Affine3d &tr)
Send setpoint to FCU position controller.
PluginBase()
Plugin constructor Should not do anything before initialize()
bool getParam(const std::string &key, bool &b) const
void quaternionMsgToEigen(const geometry_msgs::Quaternion &m, Eigen::Quaterniond &e)
ros::NodeHandle spg_nh
to get local position and gps coord which are not under sp_h()
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.
std::shared_ptr< MAVConnInterface const > ConstPtr
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
void set_position_target_global_int(uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, Eigen::Vector3d v, Eigen::Vector3d af, float yaw, float yaw_rate)
Message specification: https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT.
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d.
ros::Subscriber setpoint_sub
friend class SetPositionTargetGlobalIntMixin
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::Subscriber gps_sub
current GPS
void initialize(UAS &uas_) override
Plugin initializer.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SetpointPositionPlugin()
std::string to_string(timesync_mode e)
Eigen::Vector3d current_local_pos
Current local position in ENU.
T transform_frame_ecef_enu(const T &in, const T &map_origin)
Transform data expressed in ECEF frame to ENU frame.
T transform_orientation_baselink_aircraft(const T &in)
Transform from attitude represented WRT baselink frame to attitude represented WRT body frame.
This mixin adds set_position_target_local_ned()
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
Mixin for setpoint plugins.
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
void setpoint_cb(const geometry_msgs::PoseStamped::ConstPtr &req)
uint32_t old_gps_stamp
old time gps time stamp in [ms], to check if new gps msg is received
T transform_orientation_absolute_frame_aircraft_baselink(const T &in)
Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame,...
ros::Subscriber setpointg2l_sub
Global setpoint converted to local setpoint.
std::string tf_child_frame_id
ros::ServiceServer mav_frame_srv
T transform_orientation_enu_ned(const T &in)
Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame.
MAVROS Plugin base class.
bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
T param(const std::string ¶m_name, const T &default_val) const
void tf2_start(const char *_thd_name, void(SetpointPositionPlugin ::*cbp)(const geometry_msgs::TransformStamped &))
start tf listener
#define ROS_INFO_STREAM_NAMED(name, args)
friend class TF2ListenerMixin
void setpointg_cb(const geographic_msgs::GeoPoseStamped::ConstPtr &req)
This mixin adds set_position_target_global_int()
void local_cb(const geometry_msgs::PoseStamped::ConstPtr &msg)
constexpr std::underlying_type< _T >::type enum_value(_T e)
void setpointg2l_cb(const geographic_msgs::GeoPoseStamped::ConstPtr &req)
ros::Subscriber setpointg_sub
Global setpoint.
void transform_cb(const geometry_msgs::TransformStamped &transform)
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03