Browse Source

camera trigger : mavlink stream

sbg
Mohammed Kabir 10 years ago
parent
commit
95a8e29cfe
  1. 4
      msg/camera_trigger.msg
  2. 2
      src/modules/camera_trigger/camera_trigger.cpp
  3. 1
      src/modules/mavlink/mavlink_main.cpp
  4. 54
      src/modules/mavlink/mavlink_messages.cpp
  5. 36
      src/modules/uORB/topics/camera_trigger.h

4
msg/camera_trigger.msg

@ -0,0 +1,4 @@ @@ -0,0 +1,4 @@
uint64 timestamp # Timestamp when camera was triggered
uint32 seq # Image sequence

2
src/modules/camera_trigger/camera_trigger.cpp

@ -184,7 +184,7 @@ CameraTrigger::start() @@ -184,7 +184,7 @@ CameraTrigger::start()
if (_gpio_fd < 0) {
warnx("GPIO device open fail"); // TODO
warnx("GPIO device open fail");
stop();
}
else

1
src/modules/mavlink/mavlink_main.cpp

@ -1611,6 +1611,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -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:

54
src/modules/mavlink/mavlink_messages.cpp

@ -70,6 +70,7 @@ @@ -70,6 +70,7 @@
#include <uORB/topics/battery_status.h>
#include <uORB/topics/navigation_capabilities.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/camera_trigger.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_pwm_output.h>
#include <systemlib/err.h>
@ -1062,6 +1063,59 @@ protected: @@ -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:

36
src/modules/uORB/topics/camera_trigger.h

@ -1,6 +1,6 @@ @@ -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 @@ @@ -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_
#pragma once
#include <platforms/px4_defines.h>
#include <stdint.h>
#include <uORB/uORB.h>
#ifndef __cplusplus
#endif
/**
* @addtogroup topics
* @{
*/
/**
* Camera-IMU synchronisation message
*/
#ifdef __cplusplus
struct __EXPORT camera_trigger_s {
#else
struct camera_trigger_s {
#endif
uint64_t timestamp;
uint32_t seq;
#ifdef __cplusplus
uint64_t timestamp; /**< Timestamp when camera was triggered */
uint32_t seq; /**< Image sequence - reset to zero on getting trigger reset command */
#endif
};
/**
@ -63,6 +68,3 @@ struct camera_trigger_s { @@ -63,6 +68,3 @@ struct camera_trigger_s {
/* register this as object request broker structure */
ORB_DECLARE(camera_trigger);
#endif /* TOPIC_CAMERA_TRIGGER_H_ */

Loading…
Cancel
Save