Skip to content

Commit cfc72fe

Browse files
committed
setpoint_position: accept set-position-target-global-int messages
1 parent 6ce78d6 commit cfc72fe

File tree

1 file changed

+73
-3
lines changed

1 file changed

+73
-3
lines changed

mavros/src/plugins/setpoint_position.cpp

+73-3
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,11 @@
1919
#include <eigen_conversions/eigen_msg.h>
2020

2121
#include <geometry_msgs/PoseStamped.h>
22+
#include <geographic_msgs/GeoPointStamped.h>
2223

2324
#include <mavros_msgs/SetMavFrame.h>
2425
#include <mavros_msgs/GlobalPositionTarget.h>
26+
#include <mavros_msgs/PositionTarget.h>
2527

2628
#include <GeographicLib/Geocentric.hpp>
2729
//#include <GeographicLib/Geoid.hpp>
@@ -32,7 +34,7 @@ using mavlink::common::MAV_FRAME;
3234
/**
3335
* @brief Setpoint position plugin
3436
*
35-
* Send setpoint positions to FCU controller.
37+
* Send and receive setpoint positions from FCU controller.
3638
*/
3739
class SetpointPositionPlugin : public plugin::PluginBase,
3840
private plugin::SetPositionTargetLocalNEDMixin<SetpointPositionPlugin>,
@@ -44,7 +46,8 @@ class SetpointPositionPlugin : public plugin::PluginBase,
4446
sp_nh("~setpoint_position"),
4547
spg_nh("~"),
4648
tf_rate(50.0),
47-
tf_listen(false)
49+
tf_listen(false),
50+
is_map_init(false)
4851
{ }
4952

5053
void initialize(UAS &uas_)
@@ -71,6 +74,9 @@ class SetpointPositionPlugin : public plugin::PluginBase,
7174
gps_sub = spg_nh.subscribe("global_position/global", 10, &SetpointPositionPlugin::gps_cb, this);
7275
// Subscribe for current local ENU pose.
7376
local_sub = spg_nh.subscribe("local_position/pose", 10, &SetpointPositionPlugin::local_cb, this);
77+
78+
// subscriber for global origin (aka map origin)
79+
gp_origin_sub = spg_nh.subscribe("global_position/gp_origin", 10, &SetpointPositionPlugin::gp_origin_cb, this);
7480
}
7581
mav_frame_srv = sp_nh.advertiseService("mav_frame", &SetpointPositionPlugin::set_mav_frame_cb, this);
7682

@@ -81,11 +87,16 @@ class SetpointPositionPlugin : public plugin::PluginBase,
8187
} else {
8288
mav_frame = utils::mav_frame_from_str(mav_frame_str);
8389
}
90+
91+
// publish targets received from FCU
92+
setpointg_pub = sp_nh.advertise<geometry_msgs::PoseStamped>("cmd_pos", 10);
8493
}
8594

8695
Subscriptions get_subscriptions()
8796
{
88-
return { /* Rx disabled */ };
97+
return {
98+
make_handler(&SetpointPositionPlugin::handle_set_position_target_global_int),
99+
};
89100
}
90101

91102
private:
@@ -98,19 +109,23 @@ class SetpointPositionPlugin : public plugin::PluginBase,
98109
ros::Subscriber setpointg_sub; //!< GPS setpoint
99110
ros::Subscriber gps_sub; //!< current GPS
100111
ros::Subscriber local_sub; //!< current local ENU
112+
ros::Subscriber gp_origin_sub; //!< global origin LLA
101113
ros::ServiceServer mav_frame_srv;
114+
ros::Publisher setpointg_pub; //!< global position target from FCU
102115

103116
/* Stores current gps state. */
104117
//sensor_msgs::NavSatFix current_gps_msg;
105118
Eigen::Vector3d current_gps; //!< geodetic coordinates LLA
106119
Eigen::Vector3d current_local_pos; //!< Current local position in ENU
120+
Eigen::Vector3d map_origin {}; //!< origin of map frame [lla]
107121
uint32_t old_gps_stamp = 0; //!< old time gps time stamp in [ms], to check if new gps msg is received
108122

109123
std::string tf_frame_id;
110124
std::string tf_child_frame_id;
111125

112126
bool tf_listen;
113127
double tf_rate;
128+
bool is_map_init;
114129

115130
MAV_FRAME mav_frame;
116131

@@ -250,6 +265,15 @@ class SetpointPositionPlugin : public plugin::PluginBase,
250265
current_local_pos = ftf::to_eigen(msg->pose.position);
251266
}
252267

268+
/**
269+
* global origin in LLA
270+
*/
271+
void gp_origin_cb(const geographic_msgs::GeoPointStamped::ConstPtr &msg)
272+
{
273+
map_origin = {msg->position.latitude, msg->position.longitude, msg->position.altitude};
274+
is_map_init = true;
275+
}
276+
253277
bool set_mav_frame_cb(mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
254278
{
255279
mav_frame = static_cast<MAV_FRAME>(req.mav_frame);
@@ -258,6 +282,52 @@ class SetpointPositionPlugin : public plugin::PluginBase,
258282
res.success = true;
259283
return true;
260284
}
285+
286+
/* -*- rx handler -*- */
287+
288+
/**
289+
* @brief handle SET_POSITION_TARGET_GLOBAL_INT mavlink msg
290+
* handles and publishes position target received from FCU
291+
*/
292+
void handle_set_position_target_global_int(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SET_POSITION_TARGET_GLOBAL_INT &position_target)
293+
{
294+
/* check if type_mask field ignores position*/
295+
if (position_target.type_mask & (mavros_msgs::GlobalPositionTarget::IGNORE_LATITUDE | mavros_msgs::GlobalPositionTarget::IGNORE_LONGITUDE) > 0) {
296+
ROS_WARN_NAMED("setpoint", "lat and/or lon ignored");
297+
return;
298+
}
299+
300+
/* check origin has been set */
301+
if (!is_map_init) {
302+
ROS_WARN_NAMED("setpoint", "SetPositionTargetGlobal failed because no origin");
303+
}
304+
305+
/* convert lat/lon target to ECEF */
306+
Eigen::Vector3d pos_target_ecef {}; //!< local ECEF coordinates on map frame [m]
307+
GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f());
308+
try {
309+
earth.Forward(position_target.lat_int / 1E7, position_target.lon_int / 1E7, position_target.alt / 1E3,
310+
pos_target_ecef.x(), pos_target_ecef.y(), pos_target_ecef.z());
311+
}
312+
catch (const std::exception& e) {
313+
ROS_WARN_STREAM("setpoint: Caught exception: " << e.what() << std::endl);
314+
return;
315+
}
316+
317+
/* create position target PoseStamped message */
318+
auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
319+
pose->header = m_uas->synchronized_header("map", position_target.time_boot_ms);
320+
pose->pose.orientation.w = 1; // unit quaternion with no rotation
321+
322+
/* convert ECEF target to ENU */
323+
const Eigen::Vector3d local_ecef = pos_target_ecef - map_origin;
324+
tf::pointEigenToMsg(ftf::transform_frame_ecef_enu(local_ecef, map_origin), pose->pose.position);
325+
pose->pose.position.z = 0; // force z-axis to zero
326+
327+
/* publish target */
328+
setpointg_pub.publish(pose);
329+
}
330+
261331
};
262332
} // namespace std_plugins
263333
} // namespace mavros

0 commit comments

Comments
 (0)