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>
28 #include <mavros_msgs/PositionTarget.h>
29 #include <geographic_msgs/GeoPointStamped.h>
30 #include <mavros_msgs/GlobalPositionTarget.h>
33 namespace extra_plugins {
45 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
48 sp_nh(
"~guided_target"),
127 GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f());
132 catch (
const std::exception& e) {
133 ROS_WARN_STREAM(
"setpoint: Caught exception: " << e.what() << std::endl);
152 if (position_target.type_mask & (mavros_msgs::GlobalPositionTarget::IGNORE_LATITUDE | mavros_msgs::GlobalPositionTarget::IGNORE_LONGITUDE)) {
159 ROS_WARN_NAMED(
"setpoint",
"PositionTargetGlobal failed because no origin");
163 Eigen::Vector3d pos_target_ecef {};
164 GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f());
166 earth.Forward(position_target.lat_int / 1E7, position_target.lon_int / 1E7, position_target.alt / 1E3,
167 pos_target_ecef.x(), pos_target_ecef.y(), pos_target_ecef.z());
169 catch (
const std::exception& e) {
170 ROS_WARN_STREAM(
"setpoint: Caught exception: " << e.what() << std::endl);
175 auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
177 pose->pose.orientation.w = 1;
182 pose->pose.position.z = 0;
186 if (pose->pose.position.x !=
arr[0] || pose->pose.position.y !=
arr[1]) {
190 arr[0] = pose->pose.position.x;
191 arr[1] = pose->pose.position.y;
std::vector< HandlerInfo > Subscriptions
uint32_t old_gps_stamp
old time gps time stamp in [ms], to check if new gps msg is received
std::shared_ptr< MAVConnInterface const > ConstPtr
Eigen::Vector3d local_ecef
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
#define ROS_WARN_STREAM(args)
Eigen::Vector3d map_origin
oigin of map frame [lla]
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Eigen::Vector3d current_local_pos
Current local position in ENU.
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
ros::NodeHandle spg_nh
to get local position and gps coord which are not under sp_h()
std::string tf_child_frame_id
void initialize(UAS &uas_) override
T transform_frame_ecef_enu(const T &in, const T &map_origin)
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())
EIGEN_MAKE_ALIGNED_OPERATOR_NEW GuidedTargetPlugin()
Eigen::Vector3d ecef_origin
geocentric origin [m]
Eigen::Vector3d current_gps
geodetic coordinates LLA
std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp)
virtual void initialize(UAS &uas)
ros::Subscriber gp_origin_sub
global origin LLA
#define ROS_WARN_NAMED(name,...)
T param(const std::string ¶m_name, const T &default_val) const
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
void gp_origin_cb(const geographic_msgs::GeoPointStamped::ConstPtr &msg)
Send setpoint to FCU position controller.
void handle_position_target_global_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_GLOBAL_INT &position_target)
handle POSITION_TARGET_GLOBAL_INT mavlink msg handles and publishes position target received from FCU
ros::Publisher setpointg_pub
global position target from FCU
Subscriptions get_subscriptions() override
mavros_extras
Author(s): Vladimir Ermakov
, Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08