Bug in AP_Hott_Telem.cpp (Copter 4.0.4dev)

There is a minor bug in AP_Hott_Telem.cpp (Copter 4.0.4dev), probably because of a faulty Graupner documentation:
the gps_fix_char has to be the 3rd last byte in the GPS message, so the correct code is this:

void AP_Hott_Telem::send_GPS(void)
{
    // GPS message
    struct PACKED {
        uint8_t start_byte = 0x7c;    //#01 constant value 0x7c
        uint8_t gps_sensor_id = 0x8a; //#02 constant value 0x8a
        uint8_t warning_beeps;        //#03
        uint8_t sensor_id = 0xA0;     //#04 constant (?) value 0xa0
        uint16_t alarm;               //#05
        uint8_t flight_direction;     //#07 flight direction in 2 degreees/step (1 = 2degrees);
        uint16_t gps_speed_kmh;       //#08 km/h
        uint8_t pos_NS;               //#10 north = 0, south = 1
        uint16_t pos_NS_dm;           //#11 degree minutes
        uint16_t pos_NS_sec;          //#13 position seconds
        uint8_t pos_EW;               //#15 east = 0, west = 1
        uint16_t pos_EW_dm;           //#16 degree minutes
        uint16_t pos_EW_sec;          //#18 position seconds
        uint16_t home_distance;       //#20 meters
        uint16_t altitude;            //#22 meters. Value of 500 = 0m
        uint16_t climbrate;           //#24 m/s 0.01m/s resolution. Value of 30000 = 0.00 m/s
        uint8_t climbrate3s;          //#26 climbrate in m/3s resolution, value of 120 = 0 m/3s
        uint8_t gps_satelites;        //#27 sat count
        uint8_t free_char3;           //#28 ???
        uint8_t home_direction;       //#29 direction from starting point to Model position (2 degree steps)
        int16_t vel_north;            //#30 velocity north mm/s
        uint8_t speed_acc;            //#32 speed accuracy cm/s
        uint8_t gps_time_h;           //#33 UTC time hours
        uint8_t gps_time_m;           //#34 UTC time minutes
        uint8_t gps_time_s;           //#35 UTC time seconds
        uint8_t gps_time_hs;          //#36 UTC time 0.01s units
        int16_t vel_east;             //#37 velocity north mm/s
        uint8_t horiz_acc;            //#39 horizontal accuracy
        uint8_t free_char1;           //#40 displayed to right of home
        uint8_t free_char2;           //#41
        uint8_t gps_fix_char;         //#42 GPS fix character. display, 'D' = DGPS, '2' = 2D, '3' = 3D, '-' = no fix
        uint8_t version = 1;          //#43 0: GPS Graupner #33600, 1: ArduPilot
        uint8_t stop_byte = 0x7d;     //#44
    } msg {};

Thanks

Can you submit a PR to master, please

Also, if you could help adding the other sensors would be great.

Next would be to make the Graupner sensors provide data to ArduPilot :wink:

Hi @LuisVale ,
First: Thanks a lot for implementing Hott in ardupilot. The code works well and is well written, good job.

Honestly, i don’t know how to do that …

I don’t think, the other sensors are neccessary. The microcopter display works, and that’s the main thing.
On top of my wishlist would be: Making Arducopter parameters editable via textmode !

I’ve created a PR with @fs007’s changes in it here: https://github.com/ArduPilot/ardupilot/pull/13873

Is someone able to test that PR?

can you should a photo of the result before and after this change?
also, what receiver and transmitter are you testing on?

I’m using a Graupner mx-20 transmitter and a gr-16 receiver.
Here is a photo that shows the character AFTER this change. Before the change, the character isn’t shown at all.

Thanks! We’ve merged the fix into master. Please test and confirm it is good

Yes, please do this change. The documentation was correct, but for any reason we did implement it wrong.
On the mz-32 which I use, I can’t see the mistake, because it does display the 3D fix itself.

There’s another thing that could be improved in this lib:
A “D” should be shown when dgps mode is reached
(uint8_t gps_fix_char; //#42 GPS fix character display, ‘D’ = DGPS, ‘2’ =2D, ‘3’ = 3D, ‘-’ = no fix)

Sometimes it’s important to wait for dgps before arming.

In fact, the existing code doesn’t do that and RTK mode isn’t handled well also.

I would suggest something like this code (beginning line 279):

switch (gps.status()) {                 
    case AP_GPS::NO_GPS:
        msg.gps_fix_char = ' ';
        break;
    case AP_GPS::NO_FIX:
        msg.gps_fix_char = '-';
        break;
    case AP_GPS::GPS_OK_FIX_2D:
        msg.gps_fix_char = '2';
        break;
    case AP_GPS::GPS_OK_FIX_3D:
        msg.gps_fix_char = '3';
        break;
    case AP_GPS::GPS_OK_FIX_3D_DGPS:
        msg.gps_fix_char = 'D';
        break;
    default:
        msg.gps_fix_char = 'R';
        break;
    }

Again, I’m unable to test that patch myself, apart from, “does it
compile?”.