guided_target.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2022 Sanket Sharma, Randy Mackay.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <mavros/mavros_plugin.h>
18 #include <mavros/setpoint_mixin.h>
20 
21 #include <geometry_msgs/PoseStamped.h>
22 
23 #include <mavros_msgs/SetMavFrame.h>
24 #include <geographic_msgs/GeoPoseStamped.h>
25 
26 #include <GeographicLib/Geocentric.hpp>
27 
28 #include <mavros_msgs/PositionTarget.h>
29 #include <geographic_msgs/GeoPointStamped.h>
30 #include <mavros_msgs/GlobalPositionTarget.h>
31 
32 namespace mavros {
33 namespace extra_plugins {
34 
41  private plugin::SetPositionTargetLocalNEDMixin<GuidedTargetPlugin>,
42  private plugin::SetPositionTargetGlobalIntMixin<GuidedTargetPlugin>,
43  private plugin::TF2ListenerMixin<GuidedTargetPlugin> {
44 public:
45  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46 
48  sp_nh("~guided_target"),
49  spg_nh("~"),
50  tf_listen(false),
51  tf_rate(50.0),
52  is_map_init(false)
53  { }
54 
55  void initialize(UAS &uas_) override
56  {
58 
59  // tf params
60  sp_nh.param("tf/listen", tf_listen, false);
61  sp_nh.param<std::string>("tf/frame_id", tf_frame_id, "map");
62  sp_nh.param<std::string>("tf/child_frame_id", tf_child_frame_id, "target_position");
63  sp_nh.param("tf/rate_limit", tf_rate, 50.0);
64 
65  // Publish targets received from FCU
66  setpointg_pub = spg_nh.advertise<geometry_msgs::PoseStamped>("/move_base_simple/goal", 10);
67 
68 
69  // Subscriber for global origin (aka map origin).
70  gp_origin_sub = spg_nh.subscribe("global_position/gp_origin", 10, &GuidedTargetPlugin::gp_origin_cb, this);
71  }
72 
74  {
75  return {
77  };
78  }
79 
80 private:
81 
82 
85 
87 
89 
90  /* Stores current gps state. */
91  //sensor_msgs::NavSatFix current_gps_msg;
92  Eigen::Vector3d current_gps;
93  Eigen::Vector3d current_local_pos;
94 
95  Eigen::Vector3d map_origin {};
96  Eigen::Vector3d ecef_origin {};
97 
98  uint32_t old_gps_stamp = 0;
99 
100  std::string tf_frame_id;
101  std::string tf_child_frame_id;
102 
103  bool tf_listen;
104  double tf_rate;
106 
107  double arr[2] = {0, 0};
108 
109  /* -*- mid-level helpers -*- */
110 
122  {
123  ecef_origin = {msg->position.latitude, msg->position.longitude, msg->position.altitude};
127  GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f());
128  try {
129  earth.Reverse(ecef_origin.x(), ecef_origin.y(), ecef_origin.z(),
130  map_origin.x(), map_origin.y(), map_origin.z());
131  }
132  catch (const std::exception& e) {
133  ROS_WARN_STREAM("setpoint: Caught exception: " << e.what() << std::endl);
134  return;
135  }
136  is_map_init = true;
137  }
138 
139 
140 
141 
142  /* -*- rx handler -*- */
143 
149  void handle_position_target_global_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_GLOBAL_INT &position_target)
150  {
151  /* check if type_mask field ignores position*/
152  if (position_target.type_mask & (mavros_msgs::GlobalPositionTarget::IGNORE_LATITUDE | mavros_msgs::GlobalPositionTarget::IGNORE_LONGITUDE)) {
153  ROS_WARN_NAMED("setpoint", "lat and/or lon ignored");
154  return;
155  }
156 
157  /* check origin has been set */
158  if (!is_map_init) {
159  ROS_WARN_NAMED("setpoint", "PositionTargetGlobal failed because no origin");
160  }
161 
162  /* convert lat/lon target to ECEF */
163  Eigen::Vector3d pos_target_ecef {};
164  GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f());
165  try {
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());
168  }
169  catch (const std::exception& e) {
170  ROS_WARN_STREAM("setpoint: Caught exception: " << e.what() << std::endl);
171  return;
172  }
173 
174  /* create position target PoseStamped message */
175  auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
176  pose->header = m_uas->synchronized_header("map", position_target.time_boot_ms);
177  pose->pose.orientation.w = 1; // unit quaternion with no rotation
178 
179  /* convert ECEF target to ENU */
180  const Eigen::Vector3d local_ecef = pos_target_ecef - ecef_origin;
182  pose->pose.position.z = 0; // force z-axis to zero
183 
184  /* publish target */
185 
186  if (pose->pose.position.x != arr[0] || pose->pose.position.y != arr[1]) {
187  setpointg_pub.publish(pose);
188  }
189 
190  arr[0] = pose->pose.position.x;
191  arr[1] = pose->pose.position.y;
192  }
193 
194 };
195 } // namespace std_plugins
196 } // namespace mavros
197 
mavros::plugin::PluginBase::m_uas
UAS * m_uas
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
mavros::plugin::TF2ListenerMixin
msg
msg
ros::Publisher
mavros::extra_plugins::GuidedTargetPlugin::old_gps_stamp
uint32_t old_gps_stamp
old time gps time stamp in [ms], to check if new gps msg is received
Definition: guided_target.cpp:98
mavros::plugin::PluginBase::PluginBase
PluginBase()
mavros::UAS
mavros::extra_plugins::GuidedTargetPlugin::is_map_init
bool is_map_init
Definition: guided_target.cpp:105
ConstPtr
std::shared_ptr< MAVConnInterface const > ConstPtr
mavros::extra_plugins::GuidedTargetPlugin::tf_rate
double tf_rate
Definition: guided_target.cpp:104
mavros::extra_plugins::GuidedTargetPlugin::sp_nh
ros::NodeHandle sp_nh
Definition: guided_target.cpp:83
local_ecef
Eigen::Vector3d local_ecef
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
mavros::extra_plugins::GuidedTargetPlugin::map_origin
Eigen::Vector3d map_origin
oigin of map frame [lla]
Definition: guided_target.cpp:95
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros::extra_plugins::GuidedTargetPlugin::current_local_pos
Eigen::Vector3d current_local_pos
Current local position in ENU.
Definition: guided_target.cpp:93
mavros_plugin.h
tf::pointEigenToMsg
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
mavros::extra_plugins::GuidedTargetPlugin::spg_nh
ros::NodeHandle spg_nh
to get local position and gps coord which are not under sp_h()
Definition: guided_target.cpp:84
mavros::extra_plugins::GuidedTargetPlugin::tf_child_frame_id
std::string tf_child_frame_id
Definition: guided_target.cpp:101
mavros::extra_plugins::GuidedTargetPlugin::initialize
void initialize(UAS &uas_) override
Definition: guided_target.cpp:55
eigen_msg.h
mavros::extra_plugins::GuidedTargetPlugin
guided target plugin
Definition: guided_target.cpp:40
mavros::ftf::transform_frame_ecef_enu
T transform_frame_ecef_enu(const T &in, const T &map_origin)
mavros::plugin::SetPositionTargetLocalNEDMixin
ros::NodeHandle::subscribe
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())
mavros::extra_plugins::GuidedTargetPlugin::GuidedTargetPlugin
EIGEN_MAKE_ALIGNED_OPERATOR_NEW GuidedTargetPlugin()
Definition: guided_target.cpp:47
mavros::extra_plugins::GuidedTargetPlugin::ecef_origin
Eigen::Vector3d ecef_origin
geocentric origin [m]
Definition: guided_target.cpp:96
mavros
mavros::extra_plugins::GuidedTargetPlugin::current_gps
Eigen::Vector3d current_gps
geodetic coordinates LLA
Definition: guided_target.cpp:92
mavros::UAS::synchronized_header
std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp)
setpoint_mixin.h
initialize
virtual void initialize(UAS &uas)
mavros::plugin::PluginBase
mavros::extra_plugins::GuidedTargetPlugin::gp_origin_sub
ros::Subscriber gp_origin_sub
global origin LLA
Definition: guided_target.cpp:86
class_list_macros.hpp
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
mavros::extra_plugins::GuidedTargetPlugin::arr
double arr[2]
Definition: guided_target.cpp:107
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
mavros::extra_plugins::GuidedTargetPlugin::tf_listen
bool tf_listen
Definition: guided_target.cpp:103
mavros::extra_plugins::GuidedTargetPlugin::tf_frame_id
std::string tf_frame_id
Definition: guided_target.cpp:100
mavros::plugin::PluginBase::make_handler
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
mavros::extra_plugins::GuidedTargetPlugin::gp_origin_cb
void gp_origin_cb(const geographic_msgs::GeoPointStamped::ConstPtr &msg)
Send setpoint to FCU position controller.
Definition: guided_target.cpp:121
mavros::plugin::SetPositionTargetGlobalIntMixin
mavros::extra_plugins::GuidedTargetPlugin::handle_position_target_global_int
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
Definition: guided_target.cpp:149
mavros::extra_plugins::GuidedTargetPlugin::setpointg_pub
ros::Publisher setpointg_pub
global position target from FCU
Definition: guided_target.cpp:88
ros::NodeHandle
ros::Subscriber
mavros::extra_plugins::GuidedTargetPlugin::get_subscriptions
Subscriptions get_subscriptions() override
Definition: guided_target.cpp:73


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08