mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
camera_trigger: module docs for camera trigger driver (#23104)
This commit is contained in:
parent
d1db0addf9
commit
b5627f487f
@ -15,7 +15,7 @@ class ModuleDocumentation(object):
|
||||
# TOC in https://github.com/PX4/PX4-user_guide/blob/main/en/SUMMARY.md
|
||||
valid_categories = ['driver', 'estimator', 'controller', 'system',
|
||||
'communication', 'command', 'template', 'simulation', 'autotune']
|
||||
valid_subcategories = ['', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
|
||||
valid_subcategories = ['', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
|
||||
'magnetometer', 'baro', 'optical_flow', 'rpm_sensor', 'transponder']
|
||||
|
||||
max_line_length = 80 # wrap lines that are longer than this
|
||||
|
||||
@ -53,6 +53,7 @@
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <matrix/math.hpp>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
@ -924,7 +925,45 @@ CameraTrigger::status()
|
||||
|
||||
static int usage()
|
||||
{
|
||||
PX4_INFO("usage: camera_trigger {start|stop|status|test|test_power}\n");
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
|
||||
Camera trigger driver.
|
||||
|
||||
This module triggers cameras that are connected to the flight-controller outputs,
|
||||
or simple MAVLink cameras that implement the MAVLink trigger protocol.
|
||||
|
||||
The driver responds to the following MAVLink trigger commands being found in missions or recieved over MAVLink:
|
||||
|
||||
- `MAV_CMD_DO_TRIGGER_CONTROL`
|
||||
- `MAV_CMD_DO_DIGICAM_CONTROL`
|
||||
- `MAV_CMD_DO_SET_CAM_TRIGG_DIST`
|
||||
- `MAV_CMD_OBLIQUE_SURVEY`
|
||||
|
||||
The commands cause the driver to trigger camera image capture based on time or distance.
|
||||
Each time an image capture is triggered, the `CAMERA_TRIGGER` MAVLink message is emitted.
|
||||
|
||||
A "simple MAVLink camera" is one that supports the above command set.
|
||||
When configured for this kind of camera, all the driver does is emit the `CAMERA_TRIGGER` MAVLink message as expected.
|
||||
The incoming commands must be forwarded to the MAVLink camera, and are automatically emitted to MAVLink channels
|
||||
when found in missions.
|
||||
|
||||
The driver is configured using [Camera Trigger parameters](../advanced_config/parameter_reference.md#camera-trigger).
|
||||
In particular:
|
||||
|
||||
- `TRIG_INTERFACE` - How the camera is connected to flight controller (PWM, GPIO, Seagull, MAVLink)
|
||||
- `TRIG_MODE` - Distance or time based triggering, with values set by `TRIG_DISTANCE` and `TRIG_INTERVAL`.
|
||||
|
||||
[Setup/usage information](../camera/index.md).
|
||||
)DESCR_STR");
|
||||
PRINT_MODULE_USAGE_NAME("camera_trigger", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("camera");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop driver");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("status","Print driver status information");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test","Trigger one image (not logged or forwarded to GCS)");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test_power","Toggle power");
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
@ -39,8 +39,7 @@
|
||||
|
||||
#include <parameters/param.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
#define arraySize(a) (sizeof((a))/sizeof(((a)[0])))
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
class CameraInterface
|
||||
{
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user