forked from Archive/PX4-Autopilot
camera_trigger.msg: add feedback field to understand if message camera from trigger or capture driver
This commit is contained in:
parent
38c8a6ff74
commit
3f99204de2
|
@ -2,3 +2,4 @@ uint64 timestamp # time since system start (microseconds)
|
|||
uint64 timestamp_utc # UTC timestamp
|
||||
|
||||
uint32 seq # Image sequence number
|
||||
bool feedback # Trigger feedback from camera
|
||||
|
|
|
@ -104,6 +104,7 @@ CameraCapture::capture_callback(uint32_t chan_index,
|
|||
}
|
||||
|
||||
trigger.seq = _capture_seq++;
|
||||
trigger.feedback = true;
|
||||
|
||||
if (_camera_capture_feedback) {
|
||||
orb_publish(ORB_ID(camera_trigger), _trigger_pub, &trigger);
|
||||
|
|
|
@ -768,6 +768,7 @@ CameraTrigger::engage(void *arg)
|
|||
trigger.timestamp_utc = (uint64_t) tv.tv_sec * 1000000 + tv.tv_nsec / 1000;
|
||||
|
||||
trigger.seq = trig->_trigger_seq;
|
||||
trigger.feedback = false;
|
||||
|
||||
orb_publish(ORB_ID(camera_trigger), trig->_trigger_pub, &trigger);
|
||||
|
||||
|
|
Loading…
Reference in New Issue