From 0c138b7e031248ebd1a4dd07113cfffb855a7d2a Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 20 Feb 2021 17:22:58 -0500 Subject: [PATCH] mavlink: move CAMERA_TRIGGER to separate stream header --- src/modules/mavlink/mavlink_messages.cpp | 113 +--------------- .../mavlink/streams/CAMERA_TRIGGER.hpp | 122 ++++++++++++++++++ 2 files changed, 125 insertions(+), 110 deletions(-) create mode 100644 src/modules/mavlink/streams/CAMERA_TRIGGER.hpp diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index db21e1e835..a4c999af5f 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -103,6 +103,7 @@ using matrix::wrap_2pi; #include "streams/AUTOPILOT_VERSION.hpp" #include "streams/BATTERY_STATUS.hpp" #include "streams/CAMERA_IMAGE_CAPTURED.hpp" +#include "streams/CAMERA_TRIGGER.hpp" #include "streams/COLLISION.hpp" #include "streams/COMMAND_LONG.hpp" #include "streams/COMPONENT_INFORMATION.hpp" @@ -484,116 +485,6 @@ protected: } }; -class MavlinkStreamCameraTrigger : public MavlinkStream -{ -public: - const char *get_name() const override - { - return MavlinkStreamCameraTrigger::get_name_static(); - } - - static constexpr const char *get_name_static() - { - return "CAMERA_TRIGGER"; - } - - static constexpr uint16_t get_id_static() - { - return MAVLINK_MSG_ID_CAMERA_TRIGGER; - } - - uint16_t get_id() override - { - return get_id_static(); - } - - static MavlinkStream *new_instance(Mavlink *mavlink) - { - return new MavlinkStreamCameraTrigger(mavlink); - } - - bool const_rate() override - { - return true; - } - - unsigned get_size() override - { - if (_trigger_sub.advertised()) { - return MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES - + MAVLINK_MSG_ID_COMMAND_LONG_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; // TODO: MAV_CMD_DO_DIGICAM_CONTROL - } - - return 0; - } - -private: - uORB::Subscription _trigger_sub{ORB_ID(camera_trigger)}; - - /* do not allow top copying this class */ - MavlinkStreamCameraTrigger(MavlinkStreamCameraTrigger &) = delete; - MavlinkStreamCameraTrigger &operator = (const MavlinkStreamCameraTrigger &) = delete; - -protected: - explicit MavlinkStreamCameraTrigger(Mavlink *mavlink) : MavlinkStream(mavlink) - {} - - bool send() override - { - camera_trigger_s trigger; - - if ((_mavlink->get_free_tx_buf() >= get_size()) && _trigger_sub.update(&trigger)) { - mavlink_camera_trigger_t msg{}; - - msg.time_usec = trigger.timestamp; - msg.seq = trigger.seq; - - /* ensure that only active trigger events are sent */ - if (trigger.timestamp > 0) { - - mavlink_msg_camera_trigger_send_struct(_mavlink->get_channel(), &msg); - - vehicle_command_s vcmd{}; - vcmd.timestamp = hrt_absolute_time(); - vcmd.param1 = 0.0f; // all cameras - vcmd.param2 = 0.0f; // duration 0 because only taking one picture - vcmd.param3 = 1.0f; // only take one - vcmd.param4 = NAN; - vcmd.param5 = (double)NAN; - vcmd.param6 = (double)NAN; - vcmd.param7 = NAN; - vcmd.command = MAV_CMD_IMAGE_START_CAPTURE; - vcmd.target_system = mavlink_system.sysid; - vcmd.target_component = MAV_COMP_ID_CAMERA; - - MavlinkCommandSender::instance().handle_vehicle_command(vcmd, _mavlink->get_channel()); - - // TODO: move this camera_trigger and publish as a vehicle_command - /* send MAV_CMD_DO_DIGICAM_CONTROL*/ - mavlink_command_long_t digicam_ctrl_cmd{}; - - digicam_ctrl_cmd.target_system = 0; // 0 for broadcast - digicam_ctrl_cmd.target_component = MAV_COMP_ID_CAMERA; - digicam_ctrl_cmd.command = MAV_CMD_DO_DIGICAM_CONTROL; - digicam_ctrl_cmd.confirmation = 0; - digicam_ctrl_cmd.param1 = NAN; - digicam_ctrl_cmd.param2 = NAN; - digicam_ctrl_cmd.param3 = NAN; - digicam_ctrl_cmd.param4 = NAN; - digicam_ctrl_cmd.param5 = 1; // take 1 picture - digicam_ctrl_cmd.param6 = NAN; - digicam_ctrl_cmd.param7 = NAN; - - mavlink_msg_command_long_send_struct(_mavlink->get_channel(), &digicam_ctrl_cmd); - - return true; - } - } - - return false; - } -}; - class MavlinkStreamCameraCapture : public MavlinkStream { public: @@ -808,7 +699,9 @@ static const StreamListItem streams_list[] = { create_stream_list_item(), #endif // NAV_CONTROLLER_OUTPUT_HPP create_stream_list_item(), +#if defined(CAMERA_TRIGGER_HPP) create_stream_list_item(), +#endif // CAMERA_TRIGGER_HPP #if defined(CAMERA_IMAGE_CAPTURED_HPP) create_stream_list_item(), #endif // CAMERA_IMAGE_CAPTURED_HPP diff --git a/src/modules/mavlink/streams/CAMERA_TRIGGER.hpp b/src/modules/mavlink/streams/CAMERA_TRIGGER.hpp new file mode 100644 index 0000000000..64d199e304 --- /dev/null +++ b/src/modules/mavlink/streams/CAMERA_TRIGGER.hpp @@ -0,0 +1,122 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef CAMERA_TRIGGER_HPP +#define CAMERA_TRIGGER_HPP + +#include + +class MavlinkStreamCameraTrigger : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamCameraTrigger(mavlink); } + + static constexpr const char *get_name_static() { return "CAMERA_TRIGGER"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_CAMERA_TRIGGER; } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + bool const_rate() override { return true; } + + unsigned get_size() override + { + if (_camera_trigger_sub.advertised()) { + return MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + + MAVLINK_MSG_ID_COMMAND_LONG_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; // TODO: MAV_CMD_DO_DIGICAM_CONTROL + } + + return 0; + } + +private: + explicit MavlinkStreamCameraTrigger(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::Subscription _camera_trigger_sub{ORB_ID(camera_trigger)}; + + bool send() override + { + camera_trigger_s camera_trigger; + + if ((_mavlink->get_free_tx_buf() >= get_size()) && _camera_trigger_sub.update(&camera_trigger)) { + /* ensure that only active trigger events are sent */ + if (camera_trigger.timestamp > 0) { + mavlink_camera_trigger_t msg{}; + msg.time_usec = camera_trigger.timestamp; + msg.seq = camera_trigger.seq; + mavlink_msg_camera_trigger_send_struct(_mavlink->get_channel(), &msg); + + + vehicle_command_s vcmd{}; + vcmd.timestamp = hrt_absolute_time(); + vcmd.param1 = 0.0f; // all cameras + vcmd.param2 = 0.0f; // duration 0 because only taking one picture + vcmd.param3 = 1.0f; // only take one + vcmd.param4 = NAN; + vcmd.param5 = (double)NAN; + vcmd.param6 = (double)NAN; + vcmd.param7 = NAN; + vcmd.command = MAV_CMD_IMAGE_START_CAPTURE; + vcmd.target_system = mavlink_system.sysid; + vcmd.target_component = MAV_COMP_ID_CAMERA; + + MavlinkCommandSender::instance().handle_vehicle_command(vcmd, _mavlink->get_channel()); + + + // TODO: move this camera_trigger and publish as a vehicle_command + /* send MAV_CMD_DO_DIGICAM_CONTROL*/ + mavlink_command_long_t command_long_msg{}; + + command_long_msg.target_system = 0; // 0 for broadcast + command_long_msg.target_component = MAV_COMP_ID_CAMERA; + command_long_msg.command = MAV_CMD_DO_DIGICAM_CONTROL; + command_long_msg.confirmation = 0; + command_long_msg.param1 = NAN; + command_long_msg.param2 = NAN; + command_long_msg.param3 = NAN; + command_long_msg.param4 = NAN; + command_long_msg.param5 = 1; // take 1 picture + command_long_msg.param6 = NAN; + command_long_msg.param7 = NAN; + + mavlink_msg_command_long_send_struct(_mavlink->get_channel(), &command_long_msg); + + return true; + } + } + + return false; + } +}; + +#endif // CAMERA_TRIGGER_HPP