ardupilot
ardupilot copied to clipboard
AP_InertialSensor: Murata SCH16T IMU
Still need to validate on hardware. I can't tell if the IMU driver is running or not, is there anyway to quickly validate sensors on the bench? Using hal.console->printf() and printf() doesn't output anything on the debug uart.
Any suggestions for the best way to validate a new IMU?
- validate data
- validate loop rate
- validate missing samples (failed CRC, missed DRDY)
- validate driver runs without restarting (no failed register config, no failed data reads)
You can see where I added printfs at. I'm taking off for the day but when I'm back I'll keep looking around.
Hi @dakejahl,
Thanks for this. I'll leave it for others to answer your questions but I've noticed a couple of small things that will need fixing:
- could you split the larger commit into multiple commits separated by directory? In general commits should only affect a single subsystem and we do this because it makes backporting much easier.
- could you rebase on master? It looks like a PR from yesterday changed Tools/scripts/decode_devid.py file.
Thanks again
Alright I am using register_periodic_callback now, for the time delays between states I am using adjust_periodic_callback to set the next callback time, is this the correct way to do it? Should I even use the drdy pin? I don't see any examples of IMU drivers using it with an interrupt callback for scheduling the read
Alright I am using register_periodic_callback now, for the time delays between states I am using adjust_periodic_callback to set the next callback time, is this the correct way to do it? Should I even use the drdy pin? I don't see any examples of IMU drivers using it with an interrupt callback for scheduling the read
https://github.com/ArduPilot/ardupilot/blob/0a3bdbfdc9103a20eb3daf4a72dc401d21e24fc4/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp#L161
and yes those two functions are the correct way to adjust the period if you need to
@andyp1per Thanks for the help with this. I've tested this successfully and am ready for final review. You can ignore the hwdef file since those changes are just for testing. If there's anything else in the driver to change let me know. If it looks good I'll rebase on master and re-commit each file.
@andyp1per I agree with you on the update rate and filter settings, we need to do more testing to determine the best settings. I could create a parameter that configures the rate and filter settings, is this an acceptable thing to do in ardupilot? In PX4 some drivers expose parameters so the user can tweak things like this. We're developing this driver for Murata, but we don't have it integrated into a product yet so our flight testing has been limited. We flew it on PX4 and it worked well. The other consideration is SPI bus speed, at higher update rates we'd need to increase the bus speed, but right now on my frame it's external with kinda long wires.
Ideally I'd like to get this merged just to get it in and we can come back to fine tuning the settings once we have it properly integrated on a frame. Does this work?
I've disabled the filter and rebased/squashed on master. The last outstanding question is regarding update rate.
@andyp1per I agree with you on the update rate and filter settings, we need to do more testing to determine the best settings. I could create a parameter that configures the rate and filter settings, is this an acceptable thing to do in ardupilot? In PX4 some drivers expose parameters so the user can tweak things like this. We're developing this driver for Murata, but we don't have it integrated into a product yet so our flight testing has been limited. We flew it on PX4 and it worked well. The other consideration is SPI bus speed, at higher update rates we'd need to increase the bus speed, but right now on my frame it's external with kinda long wires.
Ideally I'd like to get this merged just to get it in and we can come back to fine tuning the settings once we have it properly integrated on a frame. Does this work?
Generally we don't want to do it like that - we want evidence that it works successfully on a flying vehicle complete with a log. Don't want to include code that isn't going to practically work 😄
I've disabled the filter and rebased/squashed on master. The last outstanding question is regarding update rate.
On most drivers we read at 8Khz and then downsample to the backend rate (which is configurable via INS_GYRO_RATE). This is perfectly acceptable CPU-wise. Some of the Invensense are 9Khz. If you look at the Invensensev3 driver which is our most actively maintained you can see how this is done.
Ping @dakejahl .... got some dataflash logs from a flying Copter?
@peterbarker thanks for the follow up. No I don't have any logs yet. This driver integration has fallen to the bottom of my priority list. We're waiting on some higher range versions of the chip anyway, which are more suitable for drones
