src
plugins
play_tune.cpp
Go to the documentation of this file.
1
#include <
mavros/mavros_plugin.h
>
2
#include <mavros_msgs/PlayTuneV2.h>
3
#include <cstring>
4
5
namespace
mavros
6
{
7
namespace
extra_plugins
8
{
9
class
PlayTunePlugin
:
public
plugin::PluginBase
10
{
11
public
:
12
PlayTunePlugin
() :
PluginBase
(),
nh
(
"~"
) {}
13
14
void
initialize
(
UAS
& uas_)
override
15
{
16
PluginBase::initialize
(uas_);
17
sub
=
nh
.
subscribe
(
"play_tune"
, 1, &
PlayTunePlugin::callback
,
this
);
18
}
19
20
Subscriptions
get_subscriptions
()
override
{
21
return
{
/* No subscriptions */
};
22
}
23
24
private
:
25
ros::NodeHandle
nh
;
26
ros::Subscriber
sub
;
27
28
void
callback
(
const
mavros_msgs::PlayTuneV2::ConstPtr
& tune)
29
{
30
auto
msg
= mavlink::common::msg::PLAY_TUNE_V2{};
31
m_uas
->
msg_set_target
(
msg
);
32
msg
.format = tune->format;
33
mavlink::set_string_z(
msg
.tune, tune->tune);
34
UAS_FCU
(
m_uas
)->send_message_ignore_drop(
msg
);
35
}
36
};
37
}
// namespace extra_plugins
38
}
// namespace mavros
39
40
#include <
pluginlib/class_list_macros.hpp
>
41
PLUGINLIB_EXPORT_CLASS
(
mavros::extra_plugins::PlayTunePlugin
,
mavros::plugin::PluginBase
)
mavros::plugin::PluginBase::m_uas
UAS * m_uas
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
msg
msg
mavros::plugin::PluginBase::PluginBase
PluginBase()
UAS_FCU
#define UAS_FCU(uasobjptr)
mavros::UAS
ConstPtr
std::shared_ptr< MAVConnInterface const > ConstPtr
mavros::extra_plugins::PlayTunePlugin::initialize
void initialize(UAS &uas_) override
Definition:
play_tune.cpp:14
mavros::extra_plugins::PlayTunePlugin::nh
ros::NodeHandle nh
Definition:
play_tune.cpp:25
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros_plugin.h
mavros::UAS::msg_set_target
void msg_set_target(_T &msg)
mavros::extra_plugins::PlayTunePlugin::callback
void callback(const mavros_msgs::PlayTuneV2::ConstPtr &tune)
Definition:
play_tune.cpp:28
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::PlayTunePlugin
Definition:
play_tune.cpp:9
mavros::extra_plugins::PlayTunePlugin::sub
ros::Subscriber sub
Definition:
play_tune.cpp:26
mavros
initialize
virtual void initialize(UAS &uas)
mavros::plugin::PluginBase
class_list_macros.hpp
mavros::extra_plugins::PlayTunePlugin::get_subscriptions
Subscriptions get_subscriptions() override
Definition:
play_tune.cpp:20
mavros::extra_plugins::PlayTunePlugin::PlayTunePlugin
PlayTunePlugin()
Definition:
play_tune.cpp:12
ros::NodeHandle
ros::Subscriber
mavros_extras
Author(s): Vladimir Ermakov
, Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08