diff --git a/msg/camera_trigger.msg b/msg/camera_trigger.msg new file mode 100644 index 0000000000..b4dcfe8ef3 --- /dev/null +++ b/msg/camera_trigger.msg @@ -0,0 +1,4 @@ + +uint64 timestamp # Timestamp when camera was triggered +uint32 seq # Image sequence + diff --git a/src/modules/camera_trigger/camera_trigger.cpp b/src/modules/camera_trigger/camera_trigger.cpp index 934945ada7..0ee93128e4 100644 --- a/src/modules/camera_trigger/camera_trigger.cpp +++ b/src/modules/camera_trigger/camera_trigger.cpp @@ -184,7 +184,7 @@ CameraTrigger::start() if (_gpio_fd < 0) { - warnx("GPIO device open fail"); // TODO + warnx("GPIO device open fail"); stop(); } else diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index ce2b5cb8bb..4e9e8a65f1 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1611,6 +1611,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("SYSTEM_TIME", 1.0f); configure_stream("TIMESYNC", 10.0f); configure_stream("ACTUATOR_CONTROL_TARGET0", 10.0f); + configure_stream("CAMERA_TRIGGER", 30.0f); break; case MAVLINK_MODE_OSD: diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 24f04fd74f..2b34345a6b 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -70,6 +70,7 @@ #include #include #include +#include #include #include #include @@ -1062,6 +1063,59 @@ protected: } }; + +class MavlinkStreamCameraTrigger : public MavlinkStream +{ +public: + const char *get_name() const { + return MavlinkStreamCameraTrigger::get_name_static(); + } + + static const char *get_name_static() { + return "CAMERA_TRIGGER"; + } + + uint8_t get_id() { + return MAVLINK_MSG_ID_CAMERA_TRIGGER; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) { + return new MavlinkStreamCameraTrigger(mavlink); + } + + unsigned get_size() { + return MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_camera_trigger_sub; + uint64_t _trig_time; + + /* do not allow top copying this class */ + MavlinkStreamCameraTrigger(MavlinkStreamCameraTrigger &); + MavlinkStreamCameraTrigger &operator = (const MavlinkStreamCameraTrigger &); + +protected: + explicit MavlinkStreamCameraTrigger(Mavlink *mavlink) : MavlinkStream(mavlink), + _camera_trigger_sub(_mavlink->add_orb_subscription(ORB_ID(camera_trigger))), + _trig_time(0) + {} + + void send(const hrt_abstime t) { + struct camera_trigger_s trigger; + + if (_camera_trigger_sub->update(&_trig_time, &trigger)) { + + mavlink_camera_trigger_t msg; + + msg.time_usec = trigger.timestamp; + msg.seq = trigger.seq; + + _mavlink->send_message(MAVLINK_MSG_ID_CAMERA_TRIGGER, &msg); + } + } +}; + class MavlinkStreamGlobalPositionInt : public MavlinkStream { public: diff --git a/src/modules/uORB/topics/camera_trigger.h b/src/modules/uORB/topics/camera_trigger.h index 6994dffe5e..a0d7e4cef8 100644 --- a/src/modules/uORB/topics/camera_trigger.h +++ b/src/modules/uORB/topics/camera_trigger.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2015 PX4 Development Team. All rights reserved. + * Copyright (C) 2013-2015 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 @@ -31,30 +31,35 @@ * ****************************************************************************/ -/** - * @file camera_trigger.h - * Camera-IMU synchronisation and triggering - */ +/* Auto-generated by genmsg_cpp from file /home/kabir/fork/Firmware/msg/camera_trigger.msg */ -#ifndef TOPIC_CAMERA_TRIGGER_H_ -#define TOPIC_CAMERA_TRIGGER_H_ -#include +#pragma once + #include +#include + + +#ifndef __cplusplus + +#endif /** * @addtogroup topics * @{ */ -/** - * Camera-IMU synchronisation message - */ -struct camera_trigger_s { - uint64_t timestamp; /**< Timestamp when camera was triggered */ - uint32_t seq; /**< Image sequence - reset to zero on getting trigger reset command */ - +#ifdef __cplusplus +struct __EXPORT camera_trigger_s { +#else +struct camera_trigger_s { +#endif + uint64_t timestamp; + uint32_t seq; +#ifdef __cplusplus + +#endif }; /** @@ -63,6 +68,3 @@ struct camera_trigger_s { /* register this as object request broker structure */ ORB_DECLARE(camera_trigger); - -#endif /* TOPIC_CAMERA_TRIGGER_H_ */ -