20 #include <geometry_msgs/PolygonStamped.h> 23 namespace std_plugins {
37 PluginBase::initialize(uas_);
41 bool manual_def =
false;
66 Eigen::Vector3d(p1x, p1y, p1z),
67 Eigen::Vector3d(p2x, p2y, p2z));
91 auto saa_msg = boost::make_shared<geometry_msgs::PolygonStamped>();
93 Eigen::Vector3d
p1(saa.p1x, saa.p1y, saa.p1z);
94 Eigen::Vector3d
p2(saa.p2x, saa.p2y, saa.p2z);
100 saa_msg->header.frame_id =
frame_id;
103 saa_msg->polygon.points.resize(2);
104 saa_msg->polygon.points[0].x = p1.x();
105 saa_msg->polygon.points[0].y = p1.y();
106 saa_msg->polygon.points[0].z = p1.z();
107 saa_msg->polygon.points[1].x = p2.x();
108 saa_msg->polygon.points[1].y = p2.y();
109 saa_msg->polygon.points[1].z = p2.z();
111 safetyarea_pub.
publish(saa_msg);
129 mavlink::common::msg::SAFETY_SET_ALLOWED_AREA
s = {};
155 if (req->polygon.points.size() != 2) {
156 ROS_ERROR_NAMED(
"safetyarea",
"SA: Polygon should contain only two points");
167 Eigen::Vector3d
p1(req->polygon.points[0].x, req->polygon.points[0].y, req->polygon.points[0].z);
168 Eigen::Vector3d
p2(req->polygon.points[1].x, req->polygon.points[1].y, req->polygon.points[1].z);
MAVROS Plugin base class.
void safetyarea_cb(const geometry_msgs::PolygonStamped::ConstPtr &req)
std::shared_ptr< MAVConnInterface const > ConstPtr
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
Safety allopwed area plugin.
ros::NodeHandle safety_nh
void msg_set_target(_T &msg)
ros::Publisher safetyarea_pub
#define ROS_INFO_STREAM_NAMED(name, args)
PluginBase()
Plugin constructor Should not do anything before initialize()
#define ROS_DEBUG_NAMED(name,...)
ros::Subscriber safetyarea_sub
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
T transform_frame_ned_enu(const T &in)
Transform data expressed in NED to ENU frame.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
T transform_frame_enu_ned(const T &in)
Transform data expressed in ENU to NED frame.
void handle_safety_allowed_area(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SAFETY_ALLOWED_AREA &saa)
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
void send_safety_set_allowed_area(Eigen::Vector3d p1, Eigen::Vector3d p2)
Send a safety zone (volume), which is defined by two corners of a cube, to the FCU.
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_NAMED(name,...)
void initialize(UAS &uas_) override
Plugin initializer.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
constexpr std::underlying_type< _T >::type enum_value(_T e)