19 #include <mavros_msgs/CamIMUStamp.h> 22 namespace extra_plugins{
55 void handle_cam_trig(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::CAMERA_TRIGGER &ctrig)
57 auto sync_msg = boost::make_shared<mavros_msgs::CamIMUStamp>();
60 sync_msg->frame_seq_id = ctrig.seq;
void publish(const boost::shared_ptr< M > &message) const
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
void handle_cam_trig(const mavlink::mavlink_message_t *msg, mavlink::common::msg::CAMERA_TRIGGER &ctrig)
ros::NodeHandle cam_imu_sync_nh
ros::Time synchronise_stamp(uint32_t time_boot_ms)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void initialize(UAS &uas_)
std::vector< HandlerInfo > Subscriptions
void initialize(UAS &uas_)
ros::Publisher cam_imu_pub
Subscriptions get_subscriptions()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)