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

Vector NAV GPS driver #5459

Closed
wants to merge 21 commits into from
Closed

Vector NAV GPS driver #5459

wants to merge 21 commits into from

Conversation

SweeWarman
Copy link

Added a new driver to read Vector NAV GPS modules. http://www.vectornav.com/products/vn200-rugged

Copy link
Contributor

@WickedShell WickedShell left a comment

Choose a reason for hiding this comment

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

I'm actually very excited to see someone playing with a vector nav and ardupilot. Have you given any thought as to adding it as a AHRS backend?

On the actual change set itself though I have a couple of questions, why are you using the group 6 messages? They are all the INS processed versions on the vectornav, which would mean feeding the EKF with data that has already been through a EKF once. If this is just a GPS driver, then this should only be using the GPS message, and the group 6 message shouldn't be used at all.

Have you flown this yet?

I made a couple of other style/implementation comments (and haven't looked at any of the time helper stuff yet).

@@ -341,6 +343,8 @@ AP_GPS::detect_instance(uint8_t instance)
if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
dstate->current_baud = 0;
}

Copy link
Contributor

Choose a reason for hiding this comment

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

Extra whitespace

@@ -298,6 +299,7 @@ AP_GPS::detect_instance(uint8_t instance)
}

if (_port[instance] == nullptr) {

Copy link
Contributor

Choose a reason for hiding this comment

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

Whitespace

@@ -468,6 +476,7 @@ AP_GPS::update_instance(uint8_t instance)
}

// we have an active driver for this instance

Copy link
Contributor

Choose a reason for hiding this comment

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

Whitespace

memset(dataPl,0,600);
if(c == 0xFA){
packetsize = 0;
packetsize++;
Copy link
Contributor

Choose a reason for hiding this comment

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

This manipulation of packetsize is extremely confusing, you only use it as an index into the array, so packetsize shouldn't be incremented here, as there is no data in the array yet, and that way you don't need to do a - 1 every time you try to write to it.

case 0:
// Checking for header
count = 0;
memset(dataPl,0,600);
Copy link
Contributor

Choose a reason for hiding this comment

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

Use the array length macro, rather then a magic number.

//state.horizontal_accuracy = msg4.PosU[0]*100;
//state.vertical_accuracy = msg4.PosU[2]*100;
state.have_horizontal_accuracy = false;
state.have_vertical_accuracy = false;
Copy link
Contributor

Choose a reason for hiding this comment

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

These are available in message 4.

state.have_speed_accuracy = true;
state.speed_accuracy = msg6.VelU;
state.num_sats = msg4.NumSats;
state.hdop = 130;
Copy link
Contributor

Choose a reason for hiding this comment

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

If the DOP's aren't available (which they aren't) this should be 9999 rather then a fake/incorrect DOP.

state.ground_course = wrap_360(degrees(atan2f(state.velocity.y, state.velocity.x)));
state.ground_speed = norm(state.velocity.y, state.velocity.x);
state.have_speed_accuracy = true;
state.speed_accuracy = msg6.VelU;
Copy link
Contributor

Choose a reason for hiding this comment

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

This should be group 4.

state.have_vertical_accuracy = false;

state.have_vertical_velocity = true;
state.velocity.x = msg6.VelNed[0];
Copy link
Contributor

Choose a reason for hiding this comment

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

Group 4

uint16_t CRC = 0;
int packetsize = 0;

uint8_t dataPl[600];
Copy link
Contributor

Choose a reason for hiding this comment

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

Rather then always being 600 bytes, this should be sized to the expected payload length, using a #define

@SweeWarman
Copy link
Author

Yes. I've flown this with a pixhawk + DJI S1000. I was thinking of using it as the AHRS backend. I'll incorporate the suggested changes. Thanks!

@OXINARF
Copy link
Member

OXINARF commented Dec 30, 2016

This needs to be rebased on master, with commits updating submodules removed as well as the commits already in master.

Also, your commit messages aren't following our contribution guidelines (ardupilot.org/dev/docs/submitting-patches-back-to-master.html). And I think all those commits can be squashed into one. We are available to help with anything in Gitter chat (http://gitter.im/ArduPilot/ardupilot).

@Kiwa21
Copy link

Kiwa21 commented Apr 22, 2018

@SweeWarman @WickedShell
Any will to update this? a VectorNav AHRS driver would be very cool for Ardupilot :)

@SweeWarman
Copy link
Author

SweeWarman commented Apr 23, 2018

@Kiwa21 someday when I finally get the time! <sigh!>

@WickedShell
Copy link
Contributor

Closing for now, as this needs to be updated. Feel free to reopen if you get the time to work on this again.

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