Closed lkoegel closed 6 years ago
Hi
/dev/spidev0.0
is correct?Hi Beat
Thank you very much for your quick reply!
Port /dev/spidev0.0
seems to be correct
This is an GPS Example stating (in line 7) that the GPS receiver is connected as an SPI device on 0.0 https://github.com/emlid/Navio2/blob/master/C%2B%2B/Examples/GPS/gps.cpp
Just tried every /dev/spidev0.*
(0-3) ort and no one worked.
@bkueng Any additional insights?
Hey everyone,
Emlid most recently changed their webpage instructing the Raspberry Pi configuration. ( https://docs.emlid.com/navio2/common/ardupilot/configuring-raspberry-pi/ ) This is a Stretch (Debian) image witch doesn't support the GPS somehow.
Beat indicated to try it out with the older Debian Version Jessie (which was on the Emlid homepage before the last change). With Jessie the GPS works. I'm still running in some trouble with the ekf2 but I'm looking in to it. Here is a log file. Maybe someone is able to find what I'm missing. https://review.px4.io/plot_app?log=3000a063-b582-438f-ad62-6ed467fd3739
Great Thanks for your help so far Beat!
Cheers Louis
I am running into this same issue. I have a RPI 3B+ and the Navio2. I am using the current image from Emlid (which is Stretch). GPS works fine with Ardupilot. When I run PX4, I get Status:NOT OK.
Is the Jessie image still available? I did not see a way to get to it from the Emlid website.
More importantly, has anyone been looking into the root cause of the issue? I was going to start looking into it, but if someone has started or has ideas as to what is going on I would love to hear about it.
Thanks!
I think I have found the issue and resolved it for my purposes. I would consider this a bug in PX4. I will say what I did to resolve the issue and if there is someone that is more familiar with the development process for PX4 maybe they can incorporate a proper fix in the main code.
I think the main issue was that the SPI clock was going too fast. I found this link on the RPI forum. https://www.raspberrypi.org/forums/viewtopic.php?t=177965 Which indicates there is a SPI clock difference between Jesse and Stretch. It seems that if the clk speed is not explicitly set then it defaults, really fast. When I looked at the SPI clock line on the board this was confirmed. The clk rate was too fast for the RPI to properly drive it.
I added IOCTL code to GPS::run()
void
GPS::run()
{
if (!_fake_gps) {
/ open the serial port /
_serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
if (_serial_fd < 0) {
PX4_ERR("GPS: failed to open serial port: %s err: %d", _port, errno);
return;
}
if(_interface == GPSHelper::Interface::SPI)
{
int spi_speed = 1000000;
int status_value = ioctl(_serial_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);
if (status_value < 0)
{
PX4_ERR("GPS: failed to set serial port write speed: %s err: %d", _port, errno);
return;
}
status_value = ioctl(_serial_fd, SPI_IOC_RD_MAX_SPEED_HZ, &spi_speed);
if (status_value < 0)
{
PX4_ERR("GPS: failed to set serial port read speed: %s err: %d", _port, errno);
return;
}
}
}
Hopefully someone who knows what they are doing can look at this and incorporate a proper patch into the main code.
Thanks!
Thanks for looking into this @mccandlt. PR is here: https://github.com/PX4/Firmware/pull/10749
Bug Report
Hi everyone, Just downloaded the most recent PX4/Firmware (master-Branch) build it on the Raspberry Pi 3 Model B. After building an running PX4 the GPS status shows:
pxh> gps status INFO [gps] Main GPS INFO [gps] protocol: UBX INFO [gps] port: /dev/spidev0.0, baudrate: 0, status: NOT OK INFO [gps] sat info: disabled
It seems that it was an issue before https://github.com/PX4/Firmware/pull/5440
Already tested out with Ardupilot if my hardware had a problem. But with Ardupilot I could find satellites.
Thank you for your help!