Remove ppk capture from input capture

F
This commit is contained in:
Jaeyoung Lim 2023-08-14 15:24:36 +02:00
parent 984467b83b
commit 5e64e9e08e
4 changed files with 30 additions and 79 deletions

View File

@ -330,6 +330,12 @@ else
fi
fi
# PPS capture driver
if param greater -s INPUT_CAP_ENABLE 0
then
input_capture start
fi
#
# Sensors System (start before Commander so Preflight checks are properly run).
# Commander needs to be this early for in-air-restarts.

View File

@ -88,7 +88,7 @@ InputCapture::InputCapture() :
}
}
_trigger_pub.advertise();
_capture_pub.advertise();
}
InputCapture::~InputCapture()
@ -157,7 +157,7 @@ InputCapture::publish_trigger()
_trigger_rate_failure.store(false);
}
camera_trigger_s trigger{};
input_capture_s trigger{};
// MODES 1 and 2 are not fully tested
if (_camera_capture_mode == 0 || _gpio_capture) {
@ -194,33 +194,13 @@ InputCapture::publish_trigger()
}
trigger.feedback = true;
_capture_overflows = _trigger.overflow;
if (!publish) {
return;
}
pps_capture_s pps_capture;
if (_pps_capture_sub.update(&pps_capture)) {
_pps_hrt_timestamp = pps_capture.timestamp;
_pps_rtc_timestamp = pps_capture.rtc_timestamp;
}
if (_pps_hrt_timestamp > 0) {
// Last PPS RTC time + elapsed time to the camera capture interrupt
trigger.timestamp_utc = _pps_rtc_timestamp + (trigger.timestamp - _pps_hrt_timestamp);
} else {
// No PPS capture received, use RTC clock as fallback
timespec tv{};
px4_clock_gettime(CLOCK_REALTIME, &tv);
trigger.timestamp_utc = ts_to_abstime(&tv) - hrt_elapsed_time(&trigger.timestamp);
}
_trigger_pub.publish(trigger);
_capture_pub.publish(trigger);
}
void

View File

@ -50,7 +50,7 @@
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/camera_trigger.h>
#include <uORB/topics/input_capture.h>
#include <uORB/topics/pps_capture.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
@ -100,11 +100,10 @@ private:
// Publishers
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
uORB::Publication<camera_trigger_s> _trigger_pub{ORB_ID(camera_trigger)};
uORB::Publication<input_capture_s> _capture_pub{ORB_ID(input_capture)};
// Subscribers
uORB::Subscription _command_sub{ORB_ID(vehicle_command)};
uORB::Subscription _pps_capture_sub{ORB_ID(pps_capture)};
// Trigger Buffer
struct _trig_s {

View File

@ -31,57 +31,23 @@
*
****************************************************************************/
// /**
// * @file camera_capture_params.c
// * Camera capture parameters
// *
// * @author Mohammed Kabir <kabir@uasys.io>
// */
// /**
// * Camera strobe delay
// *
// * This parameter sets the delay between image integration start and strobe firing
// *
// * @unit ms
// * @min 0.0
// * @max 100.0
// * @decimal 1
// * @group Camera Capture
// */
// PARAM_DEFINE_FLOAT(CAM_CAP_DELAY, 0.0f);
/**
* @file input_capture_params.c
* Input capture parameters
*
* @author Mohammed Kabir <kabir@uasys.io>
* @author Jaeyoung Lim <jalim@ethz.ch>
*/
// /**
// * Camera capture feedback
// *
// * Enables camera capture feedback
// *
// * @boolean
// * @group Camera Control
// * @reboot_required true
// */
// PARAM_DEFINE_INT32(CAM_CAP_FBACK, 0);
// /**
// * Camera capture timestamping mode
// *
// * Change time measurement
// *
// * @value 0 Get absolute timestamp
// * @value 1 Get timestamp of mid exposure (active high)
// * @value 2 Get timestamp of mid exposure (active low)
// *
// * @group Camera Control
// * @reboot_required true
// */
// PARAM_DEFINE_INT32(CAM_CAP_MODE, 0);
// /**
// * Camera capture edge
// *
// * @value 0 Falling edge
// * @value 1 Rising edge
// *
// * @group Camera Control
// * @reboot_required true
// */
// PARAM_DEFINE_INT32(CAM_CAP_EDGE, 0);
/**
* Input Capture Enable
*
* Enables the PPS capture module.
* This switches mode of FMU channel 7 to be the
* PPS input channel.
*
* @boolean
* @group Camera Control
* @reboot_required true
*/
PARAM_DEFINE_INT32(INPUT_CAP_ENABLE, 0);