drivers: video: hm01b0 - reset/pwdn more formats#98154
drivers: video: hm01b0 - reset/pwdn more formats#98154KurtE wants to merge 3 commits intozephyrproject-rtos:mainfrom
Conversation
e39c928 to
503e7b1
Compare
josuah
left a comment
There was a problem hiding this comment.
Thanks for these improvements!
Here are a few suggestions to try to reduce the code size and some help for implementing frame rate control.
Let me know if you have questions!
|
@josuah @mjs513 - What my gut tells me, is there are some wrong settings for 324x324 versus 244x324 So it showed the 324x324, however if I look at the Logic Analyzer output It shows 244 rows output: But if I configure by 324x244: But logic analyzer output shows: |
909b1aa to
53af77b
Compare
|
Quick note: with the help of @mjs513 found the format issue and fixed. I am going to mark as ready for review again. Also unless I hear otherwise, I will |
|
@avolmat-st |
avolmat-st
left a comment
There was a problem hiding this comment.
Thanks @KurtE, sorry (again), one last small wording in the migration-guide tp integrate it better in the generated documentation.
4f9ba21 to
b0eeb8b
Compare
|
Hi @KurtE, |
|
avolmat-st
left a comment
There was a problem hiding this comment.
I have some doubt about the power-down / reset handling, could you check ?
Also, thanks, but no need to add me as Co-Authored-by in the commit, but if you really want to, my email address is : alain.volmat@foss.st.com
| if (!gpio_is_ready_dt(&config->pwdn)) { | ||
| return -ENODEV; | ||
| } | ||
| ret = gpio_pin_configure_dt(&config->pwdn, GPIO_OUTPUT_ACTIVE); |
There was a problem hiding this comment.
Could you clarify the level expected by the sensor and what is set at the device-tree level for this pin ?
Here this indicated that the powerdown pin is set to ACTIVE state in order to work, which doesn't feel right, or maybe the pin isn't correctly named ?
| if (!gpio_is_ready_dt(&config->reset)) { | ||
| return -ENODEV; | ||
| } | ||
| ret = gpio_pin_configure_dt(&config->reset, GPIO_OUTPUT_ACTIVE); |
There was a problem hiding this comment.
Same here for the reset pin. It set it to ACTIVE state before using the sensor. I'd have expected to have probably both powerdown and reset pin set to INACTIVE state in order to have the sensor in normal condition of usage. Moreover, is there a reset sequence available ? Such as ensure that the sensor is kept in reset state at least xx usec before release the reset etc ?
As an example, for the imx335 sensor:
#if DT_ANY_INST_HAS_PROP_STATUS_OKAY(reset_gpios)
if (cfg->reset_gpio.port != NULL) {
if (!gpio_is_ready_dt(&cfg->reset_gpio)) {
LOG_ERR("%s: device %s is not ready", dev->name,
cfg->reset_gpio.port->name);
return -ENODEV;
}
/* Power up sequence */
ret = gpio_pin_configure_dt(&cfg->reset_gpio, GPIO_OUTPUT_ACTIVE);
if (ret) {
return ret;
}
k_sleep(K_NSEC(500)); /* Tlow */
gpio_pin_set_dt(&cfg->reset_gpio, 0);
k_sleep(K_USEC(600)); /* T4 */
}
#endifYou can see above that at the end of the sequence the reset state is at INACTIVE (0). Which doesn't actually mean that the pin is at 0, it can also be 1 if within the device-tree the gpio is written as ACTIVE_LOW.
There was a problem hiding this comment.
Based at what is written in the binding, the reset is mentioned at a ACTIVE_LOW signal (which makes sense since it is named RESETn. In such case, in the device-tree the pin should be written as ACTIVE_LOW (I guess it is written currently as ACTIVE_HIGH would would make the current code work), and the driver must set the reset state at 0 before starting to use the sensor.
There was a problem hiding this comment.
The interesting issue with these signals is that camera adapter boards are not consistent with each other or the
specs of the camera. I know that the two different boards/camera I have done most of my testing on are opposite
of each other. One wants the reset high the other wants it low... Which is why I had the try all combinations code in
earlier. Probably in the Arduino case, I will probably propose in the Arduino camera library that it do the different
combinations, until it finds one that works.
Edit: Actually on the Arduino, with the Portenta H7, not sure what I would suggest, as not only does these signals differ in High versus Low, but the Carrier boards also use a different IO pin (same PWM signal) for the Camera clock. (Vision Shield, versus Mid Carrier with Arduino/Arducam HM01b0 camera),
There was a problem hiding this comment.
I am not that surprised that the signal polarity might be different from one board to another even when dealing with the same sensor. This is why it is important at the driver level to make it as "activate / desactive reset or pwdn" and then the what this means in term of signal level is then written into the device-tree in each of those board shield.
There was a problem hiding this comment.
I hear you,
but so far Arduino has not defined Zephyr shields for each of their Portenta shield and Carrier boards, nor defined how one would have access to them in Arduino. Like do you create a variant for each valid combination. Each of their variants adds a lot of disk space to the builds and releases. Currently for each board like the Portenta H7 and Giga there is just one variant defined.
I have asked a few different times, like in arduino/ArduinoCore-zephyr#127
There was a problem hiding this comment.
A potential way to go could also simply by to rely on gpio-hog since finally the driver isn't doing much control on the reset / powerdown gpio, simply ensuring that they are at the right level to enable the sensor. In such case, a gpio-hog, defined within the device-tree on the corresponding GPIO adapter could be enough. cf dts/bindings/gpio/gpio-controller.yaml
There was a problem hiding this comment.
Some of their documents don't show much, you have to sort of read between the lines:
For the Arducam/Arduino HM01b0: Arduino sells them:
https://store.arduino.cc/products/hm01b0-qvga-monochrome-dvp-camera-module-for-arduino-giga-r1-wifi-board?queryID=undefined
Their schematic shows almost nothing:
https://www.uctronics.com/download/Datasheet/Arducam-HM01B0.pdf
If I remember correctly their Shutdown, may actually go to a Voltage regulator on the board that supplies power to the camera.
A sparkfun (color) version, I have:
https://www.sparkfun.com/sparkfun-red-vision-camera-board-hm01b0-color.html
Schematic: https://cdn.sparkfun.com/assets/a/0/b/1/7/SparkFun_Red_Vision_Camera_Board_HM01B0.pdf
This one shows these IO pins again going to Voltage Regulator.
The Arduino Vision shield I mentioned:
https://store.arduino.cc/collections/portenta-family/products/portenta-vision-shield-ethernet
Schematic:
https://docs.arduino.cc/resources/schematics/ASX00026-schematics.pdf
(I believe Page 9 of it has LDO page with the logical power down pin going to the VR. In this case I don't believe
they hooked up any logical Rest pin.
There was a problem hiding this comment.
I hear you, but so far Arduino has not defined Zephyr shields for each of their Portenta shield and Carrier boards, nor defined how one would have access to them in Arduino.
@KurtE, what you are proposing to merge is a Zephyr driver, and so it has to be developed using the full DT abstractions so that all Zephyr users can benefit from it. Arduino may then make use of it downstream in some way, but this should not define or restrict its development.
(OTOH, defining shields is absolutely the way to go for Zephyr upstream in this case, and contributions are warmly welcome! 😉)
There was a problem hiding this comment.
Thanks @pillo79 - I totally understand what you are saying about enhancing these drivers, helps all who develop using native Zephyr as the build environment. Likewise, for developing shields. Although my guess is that those might
take years to be integrated.
But not sure how well it works yet with the Arduino on top of Zephyr, with the camera stuff. How to switch cameras,
how to handle differences in hardware like maybe RESET is high on one carrier board and low on another, How do
I not pay a penalty (memory usage, hardware usage, power) for those sketches I do that don't use a camera. And do all of this without having each user have to install ArduinoCore-zephyr/zephyr build system and build a new bootloader, just to switch any of these things. Sometimes feels like trying to use a square peg in a round hole.
At times I am tempted to see how hard it would be to bypass all of this stuff, and be able to optionally enable a camera and drive DCMI directly... Or something completely different 🤔
There was a problem hiding this comment.
Connecting the threads together just for convenience:
| reset-gpios: | ||
| type: phandle-array | ||
| description: | | ||
| The RESETn pin is asserted to disable the sensor causing a hard | ||
| reset. The sensor receives this as an active-low signal. | ||
| pwdn-gpios: | ||
| type: phandle-array | ||
| description: | | ||
| The PWDN pin is asserted to power down the sensor. The sensor | ||
| receives this as an active high signal |
There was a problem hiding this comment.
Please correct me if I am wrong but, based on the PDF I shared in the conversation, the sensor itself doesn't have reset / pwdn pin so at least the descriptions does not seem correct.
Did I misread the PDF or didn't get the right one ?
There was a problem hiding this comment.
As I mentioned in another response. I believe you are right, in that the sensor itself may not have direct support
for these pins, but many/most of the carrier boards do. In particular the ones I mentioned do this by turning
off the power by disabling a voltage regulator, that supplies the power to the camera. Obviously we can change
the wording here if you like. Suggestion?
There was a problem hiding this comment.
Did you had a chance to have a look at gpio-hog I mentioned yesterday and see it would fit your need ? I think that in current situation / usage of those pins, actually gpio-hog might be enough.
There was a problem hiding this comment.
Thanks @avolmat-st - I took a look at the HOG stuff, and yes it might be able to work for specific cases of
known up front always start up the camera setups.
But so far I have resisted for a couple of reasons.
-
I would not use this in the case of Arduino (assuming that defer init code is pulled in), as I would not wish to
use those pin resources unless my sketch actually uses a camera. -
Maybe it is just me, but I prefer to have a more consistent approach for how to handle these types of pins
between cameras. That is when setting up to use one of the many different cameras with the same pin pattern
like:
It would be nice if there was some common approach. Would be even nicer if they all had plus and minus
consistent, but...
- At some point, apps may want to gain access to those IO pins and for example turn off the camera if it
is not going to use it for a significant amount of time.
But suggesting the HOG has one advantage, in that I suppose we could punt and remove it from the PR and say it is up to the users to decide how to get these pins set?
|
Everyone not sure what I should do here for reset/powerdown pins. As mentioned the camera chip itself does not actually know about these signals, but most carrier board do. Unfortionatly Or as I have it now where the board definition has it correct, which works some of the times, but for example on Arduino boards using LLText and if for example the Sparkfun camera is not compatible with the Arducam one what do you do? One option I GPIO Hog - I think defines the sate in the device tree? That is the pins are set to specific state as part of the system startup? Or punt? Thanks |
Adding some of the missing pieces to the HM01b0 video class. changed the VIDEO define to match all of the other video drivers that I have tried: That is CONFIG_VIDEO_HIMAX_HM01B0 to CONFIG_VIDEO_HM01B0 Added PWDN and RESET pins, to yaml, plus code. Added a few more format sizes: 324x324 to 324x244 164x122 match the spec. Added BAYER format for the color camera (VIDEO_PIX_FMT_SBGGR8) Only for Full, and QVGA, as cameras with BAYER filter do not support the binning mode. Added 4 data bit support, using new format: VIDEO_PIX_FMT_Y4 Support for hflip/vflip controls. Added the frmival set/get/enum functions, to allow us better control of how many frames are generated per second. Used the reset register enumeration similar to other implementions, such as Arduino library, Teensy Library, and OpenME Signed-off-by: Kurt Eckhardt <kurte@rockisland.com>
Rename the config CONFIG_VIDEO_HIMAX_HM01B0 to CONFIG_VIDEO_HM01B0 Signed-off-by: Kurt Eckhardt <kurte@rockisland.com> Co-Authored-By: Alain Volmat <58030053+avolmat-st@users.noreply.github.com>
|









Now that the @NinoSc PR has been merged:
Adding some of the missing pieces to the HM01b0 video class.
Note: not maybe necessary, but changed the VIDEO define to match all of the other video drivers that I have tried:
That is CONFIG_VIDEO_HIMAX_HM01B0 to
CONFIG_VIDEO_HM01B0
Also keep wondering if the default data-bits should be 8 as to be more likely compatible with more camera drivers. But
left it as 1.
Added PWDN and RESET pins, to yaml, plus code.
Added a few more format sizes: 326x326 to 326x244 match the spec. Verified again from earlier
tests, and Logic Analyzer.
I have also added some of the other components that are in other related drivers, like the
ctrl for HFLIP/VFlip
Added 4 bit mode using the format @avolmat-st suggested in the related issue.
Added format for cameras with Bayer filter.
Questions are:
Should I remove the current resolutions like: 320x320 as the camera does not actually return that?
The images are not as good as I would like or saw from the cameras on other setups. I believe a lot of
this is the other setups (Arducam, Linux, Teensy) do a lot settings of the registers than this currently does.
Things like Auto Exposure and the like.
Main question is: what granularity of change would you prefer to see?
Continue on to refine the images? Or incremental steps? Should I squash all of these?
Do you agree with the cahnge from CONFIG_VIDEO_HIMAX_HM01B0 -> CONFIG_VIDEO_HM01B0 or should I revert it?
Thanks
Kurt