19 #include <mavros_msgs/ActuatorControl.h> 22 namespace std_plugins {
36 PluginBase::initialize(uas_);
59 auto actuator_control_target_msg = boost::make_shared<mavros_msgs::ActuatorControl>();
62 actuator_control_target_msg->group_mix = actuator_control_target.group_mlx;
63 const auto &arr = actuator_control_target.controls;
64 std::copy(arr.cbegin(), arr.cend(), actuator_control_target_msg->controls.begin());
66 target_actuator_control_pub.
publish(actuator_control_target_msg);
74 mavlink::common::msg::SET_ACTUATOR_CONTROL_TARGET act{};
76 act.time_usec = req->header.stamp.toNSec() / 1000;
77 act.group_mlx = req->group_mix;
80 std::copy(req->controls.begin(), req->controls.end(), act.controls.begin());
MAVROS Plugin base class.
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
std::shared_ptr< MAVConnInterface const > ConstPtr
void handle_actuator_control_target(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ACTUATOR_CONTROL_TARGET &actuator_control_target)
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))
PluginBase()
Plugin constructor Should not do anything before initialize()
uint8_t get_tgt_system()
Return communication target system.
void initialize(UAS &uas_)
Plugin initializer.
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
void actuator_control_cb(const mavros_msgs::ActuatorControl::ConstPtr &req)
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Compute FCU message time from time_boot_ms or time_usec field.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher target_actuator_control_pub
ros::Subscriber actuator_control_sub
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
uint8_t get_tgt_component()
Return communication target component.