Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Pr camera capture driver #11395

Merged
merged 24 commits into from
Feb 10, 2019
Merged

Pr camera capture driver #11395

merged 24 commits into from
Feb 10, 2019

Conversation

DanielePettenuzzo
Copy link
Contributor

@DanielePettenuzzo DanielePettenuzzo commented Feb 6, 2019

This pr replaces #10295 because support was added also for the av-x board that currently doesn't have timer input capture available, therefore we are using gpio captures. This is not ideal but the goal is to get this merged and then do a second iteration where we add timer capture support for the av-x board.

mhkabir and others added 24 commits February 5, 2019 16:25
… camera feedback module uses CAM_CAP_FBACK param to choose between the two.
   This extends the  Capture support for FMU
   CHAN 5 and 6.
@dagar dagar requested review from dagar and davids5 February 6, 2019 14:09
@DanielePettenuzzo
Copy link
Contributor Author

From previous pr:

This PR adds the camera capture driver. This can be used to receive a feedback from a camera after it is triggered (eg. sony hot shoe feedback). In this case we don't publish the camera_trigger message in the camera_trigger driver when we trigger the camera, but we publish when we receive the feedback from the camera. When geotagging images this will increase the presision in the geotag.

This can be also used to sync CV cameras with the IMU data for VIO or similar applications.

Currently only channel 5 on the FMU PWM outputs can be used for this driver. I still need to check on which outputs we can actually run this.

Some more tests will be done in the next days.

Params for testing:
CAM_CAP_FBACK = 1 (enable camera capture)

CAM_CAP_MODE =
0 (get edge timestamp)
1 (get pulse midpoint timestamp for active high triggers)
2 (get pulse midpoint timestamp for active low triggers)

CAM_CAP_EDGE =
0 (trigger on falling edge)
1 (trigger on rising edge)

CAM_CAP_DELAY --> delay between image integration start and strobe firing (default to 0)

@DanielePettenuzzo
Copy link
Contributor Author

@dagar this was tested yesterday on the av-x board and on a pixhawk 4.

@@ -269,12 +272,14 @@ CameraTrigger::CameraTrigger() :
_p_activation_time = param_find("TRIG_ACT_TIME");
_p_mode = param_find("TRIG_MODE");
_p_interface = param_find("TRIG_INTERFACE");
_p_cam_cap_fback = param_find("CAM_CAP_FBACK");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I need to better understand the overall design, but reaching into other modules params is something I'd like to avoid.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@dagar I agree. The reason for this is because when the camera_capture driver is active I rename the topic name of the camera_trigger driver so that the camera_capture can publish the camera_trigger message (which is the one that goes to the geotagging and to mavlink). Do you have any idea how this could be cleaned up? In any case, even if we want to keep this structure I think the parameter should be defined in the camera_trigger driver because otherwise this will cause issues on the targets that won't have the camera_capture driver in their cmake.

@dagar
Copy link
Member

dagar commented Feb 10, 2019

There are some minor things, but this looks safe to merge and we've been sitting on it for way too long. I'll merge now and we can continue from master.

@dagar dagar merged commit a2bb826 into PX4:master Feb 10, 2019
@dagar dagar deleted the pr-camera_capture_driver branch February 10, 2019 23:07
@jasonbeach
Copy link

@DanielePettenuzzo I'm looking at this again--so for I've built what's on master and completed a basic test it seems to work. It looks like the autopilot should publish a camera_capture message in response to the pulse. How do you access that message? If I run mavros the only related message I see published is the cam_imu_stamp message. I will also try to help out with the docs so this can get pushed into a release.

@jasonbeach
Copy link

I guess just to be clear, it looks like the camera_capture driver publishes the camera_trigger message which the camera_feedback module subscribes to and then looks like it should publish the camera_capture message. Couple things I see:

  1. the camera_feedback module doesn't run by default.
  2. from the mavlink console in qgroundcontrol I can start it but even when I do the camera_capture message doesn't appear to be getting published. (It doesn't show up on uorb top)

@AlexandreBorowczyk
Copy link

I have a quick question and it seems like the most likely place to get the answer.
Why in the following section, only one input capture is defined? what happens of the otherone?

https://github.com/PX4/Firmware/blob/dcfe226638c8d50a42f30c1c50f8c5ca4a000060/src/drivers/px4fmu/fmu.cpp#L358-L370

@davids5
Copy link
Member

davids5 commented Oct 28, 2019

@AlexandreBorowczyk - It is a mistake. There needs to be a

`up_input_capture_set(6, Rising, 0, NULL, NULL);`

added.

@AlexandreBorowczyk
Copy link

Alright Thanks for clearing things up!

@bys1123
Copy link
Contributor

bys1123 commented Nov 10, 2019

Will this have a document? @hamishwillee

@hamishwillee
Copy link
Contributor

@bys1123 One can only hope that @DanielePettenuzzo will find time. I've got a placeholder for it: PX4/PX4-user_guide#604

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

9 participants