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

Mavlink: Implemented SET_CAMERA_ZOOM #13681

Merged
merged 2 commits into from
Mar 30, 2020
Merged

Conversation

dayjaby
Copy link
Contributor

@dayjaby dayjaby commented Dec 5, 2019

Describe problem solved by this pull request
Some cameras, like the FLIR Duo Pro R, don't allow to use the MAV_CMD_SET_CAMERA_ZOOM message to control the zoom. Instead they rely on PWM values.

Describe your solution
In mavlink_receiver.cpp we react on MAV_CMD_SET_CAMERA_ZOOM if CAMERA_ZOOM_TYPE is ZOOM_TYPE_RANGE and publish the zoom control in index 4 of actuator_controls_2. This allows maximum flexibility in assigning an AUX channel. Index 4 in control group 2 is still reserved, but seems to be a good spot to place the zoom (index 3 is camera shutter).

Describe possible alternatives
One alternative would be to have a parameter similar to MNT_MAN_ROLL/PITCH/YAW where we can set the AUX channel directly. But with the mixer file approach it is possible to allow PWM scaling/reversing.

mavlink_receiver.cpp is probably not the best place to do this implementation. Maybe create an own module called "camera" where we can also handle other CAMERA_ZOOM_TYPEs?

Test data / coverage
Only in PX4/sitl_gazebo on the iris with this mixer file: https://gist.github.com/dayjaby/8e451632915cd7c3ec0934ebffca8c52 and adding set MIXER_AUX mount_zoom to ROMFS/px4fmu_common/init.d-posix/10016_iris

Doing a test on the real drone today. (Edit: works!)

Copy link
Contributor

@julianoes julianoes left a comment

Choose a reason for hiding this comment

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

Thanks for that!

}

if ((int)(cmd_mavlink.param1 + 0.5f) == 2) {
actuator_controls.control[4] = cmd_mavlink.param2 / 50.0f - 1.0f;
Copy link
Contributor

Choose a reason for hiding this comment

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

Is it documented somewhere that channel 5 is zoom?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

No, channel 5 is still reserved.

Copy link
Contributor

Choose a reason for hiding this comment

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

Hm, could you add it to the description of the channel then in the message?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I added a PR to Devguide. Is that what you expected?

Copy link
Contributor

Choose a reason for hiding this comment

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

And I would add a note or index in the msg file:
https://github.com/PX4/Firmware/blob/master/msg/actuator_controls.msg

dayjaby added a commit to dayjaby/Devguide that referenced this pull request Dec 7, 2019
Some cameras allow to control the zoom with PWM. So it makes sense to add the zoom to the actuator controls/outputs. A first implementation for handling mavlinks SET_CAMERA_ZOOM can be found in PX4/PX4-Autopilot#13681
@dayjaby dayjaby force-pushed the pr-set-camera-zoom branch 2 times, most recently from 7e6a21f to a2d8834 Compare December 16, 2019 15:16
@dayjaby dayjaby force-pushed the pr-set-camera-zoom branch from a2d8834 to bfd4ffb Compare January 27, 2020 17:04
@dayjaby
Copy link
Contributor Author

dayjaby commented Jan 27, 2020

  • added enum-like indices to actuator_controls.msg
  • allowed DO_CONTROL_VIDEO to appear in missions

uint8 GROUP_INDEX_GIMBAL = 2
uint8 GROUP_INDEX_MANUAL_PASSTHROUGH = 3
uint8 GROUP_INDEX_MC_VIRTUAL = 4
uint8 GROUP_INDEX_FW_VIRTUAL = 5
Copy link
Contributor

Choose a reason for hiding this comment

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

@sfuhrer are these correct?

Copy link
Contributor

Choose a reason for hiding this comment

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

Looking at the guide (https://dev.px4.io/master/en/concept/mixing.html) or here: yes, ordering is correct. But not sure where we would need the GROUP_INDEX of MC_VIRTUAL and FW_VIRTUAL atm.

Copy link
Contributor

Choose a reason for hiding this comment

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

@julianoes @dayjaby What needs to happen to progress this? I'm just working through my docs PRs and this is a dependency.

@@ -9,8 +9,17 @@ uint8 INDEX_FLAPS = 4
uint8 INDEX_SPOILERS = 5
uint8 INDEX_AIRBRAKES = 6
uint8 INDEX_LANDING_GEAR = 7
uint8 INDEX_GIMBAL_SHUTTER = 3
uint8 INDEX_CAMERA_ZOOM = 4
Copy link
Contributor

Choose a reason for hiding this comment

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

So these indexes are for another group, right? Otherwise they conflict.

@julianoes
Copy link
Contributor

@dayjaby can you make sure this is up-to-date and the CI passes?

@dayjaby dayjaby force-pushed the pr-set-camera-zoom branch 2 times, most recently from e8b7aa6 to ff86188 Compare March 28, 2020 06:52
@dayjaby dayjaby force-pushed the pr-set-camera-zoom branch from ff86188 to f65cadb Compare March 28, 2020 07:03
@dayjaby
Copy link
Contributor Author

dayjaby commented Mar 28, 2020

@julianoes Rebased and removed the questionable GROUP_INDEX_MC_VIRTUAL and GROUP_INDEX_FW_VIRTUAL. make format tried to change platforms/common/include/px4_platform_common/i2c_spi_buses.h in a weird manner, but I just ignored it.

Copy link
Contributor

@julianoes julianoes left a comment

Choose a reason for hiding this comment

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

Great, thanks!

@julianoes julianoes merged commit 536cd6c into PX4:master Mar 30, 2020
hamishwillee pushed a commit to PX4/PX4-Devguide that referenced this pull request Apr 2, 2020
Some cameras allow to control the zoom with PWM. So it makes sense to add the zoom to the actuator controls/outputs. A first implementation for handling mavlinks SET_CAMERA_ZOOM can be found in PX4/PX4-Autopilot#13681
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants