POSITION_TARGET_GLOBAL_INT is never sent by Arducopter despite being requested using SET_MESSAGE_INTERVAL

I was thinking it would be nice to get confirmation that the drone has received my MAVLINK_MSG_SET_POSITION_TARGET_POSITION message to send the drone to a particular location. I request that message using MAV_CMD_SET_MESSAGE_INTERVAL in my start up code.

Unfortunately, I never receive the MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT which I was expecting to get. This would hopefully tell me that the drone had updated its target to fly to.

I had a look at the Arducopter source code and found this in GCS_Mavlink.cpp:

void GCS_MAVLINK_Copter::send_position_target_global_int()
{
    Location target;
    if (!copter.flightmode->get_wp(target)) {
        return;
    }
    mavlink_msg_position_target_global_int_send(

We also have this in mode_guided.cpp:

bool ModeGuided::get_wp(Location& destination)
{
    if (guided_mode != Guided_WP) {
        return false;
    }
    return wp_nav->get_oa_wp_destination(destination);
}

So far it looks like I should be receiving it. How can I know where the drone is flying to?

Thanks.

What version of copter is this?

Would please post a TLog and a Bin Log?

I quite sure you should automatically receive that message as it is part of a stream. (Setting the message interval should be unnecessary unless you want to change the rate of the message.)

1 Like

Iā€™ll post the log tomorrow. Thanks.

@hendjosh

Please find my log here:

The password for the zip is simply my username.

I would like to add that I found my code had a mistake so it did not explicitly request the MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT message, however based on what you said, I should be seeing this message regardless.

Many thanks.

Hmm. There is only one GUID log message there. So you only tried to set the guided mode once.

What exactly are you sending over mavlink? Type-mask is extra important.

Do you have a tlog?

1 Like

It seems that the message will only get sent out for sub modes WP and POS.

Note I have a PR to fully support Position_Target_Global_Int message.

1 Like

It was doing a takeoff to 10m followed by ascent to position target another 5m up and finally an attempt to set an attitude target. To be honest, there was only one position+yaw target set (with type mask set to only allow position i.e. POSITION_TARGET_TYPEMASK_VELOCITY_IGNORE | POSITION_TARGET_TYPEMASK_ACCELERATION_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE) but still I did not see the Position_Target_Global_Int messages.

Thank you for your work on that pull request. It makes sense to have it enabled during GUIDED mode, especially since you can request position targets so why not receive confirmation of them?

I know that it is possible to receive POSITION_TARGET_LOCAL_NED when in GUIDED mode, for instance, so your pull request makes sense.

Cheers.

Are you able to receive the POSITION_TARGET_LOCAL_NED messages if you request them?

Possibly, the reason you arenā€™t getting that message is that terrain data is still pending download and thus is not available to convert the altitude frame. This means we donā€™t send Position_Target_Global_Int messages. Not 100% on this though as I canā€™t replicate the behavior in SITL.

Maybe try ensuring the terrain data is available by downloading it from the server for your locale?

My PR is just to fill out the data set further. I might follow-up with a PR to ensure for example in takeoff we send and log the targets which doesnā€™t seem to be occurring.

1 Like

My code is basically this:

    com.param1 = (float) MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
    com.param2 = (float) 500 * 1000;
    if(send_command(&com) != 0)
        return -1;

    com.param1 = (float) MAVLINK_MSG_ID_LOCAL_POSITION_NED;
    com.param2 = (float) 500 * 1000;
    if(send_command(&com) != 0)
        return -1;

    com.param1 = (float) MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
	com.param2 = (float) 250 * 1000;	// us between messages
    if(send_command(&com) != 0)
			return -1;

	com.param1 = (float) MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
	com.param2 = (float) 250 * 1000;
    return send_command(&com);

With my drone sitting on the ground unarmed, I only get MAVLINK_MSG_ID_GLOBAL_POSITION_INT and MAVLINK_MSG_ID_LOCAL_POSITION_NED messages. Do I need to be in GUIDED mode or flying to get the POSITION_TARGET messages?

Thanks.

The type-mask is set to POSITION_TARGET_TYPEMASK_VELOCITY_IGNORE | POSITION_TARGET_TYPEMASK_ACCELERATION_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE

I do not have a tlog as I am not using Mission Planner to control the drone.

I think itā€™s best that I repeat my tests with an explicit request for the position targets as by default it does not seem to work. Iā€™ll post here with updates.

Thanks for your help.

I had a look at but it seems you only need terrain data if the TERRAIN_ENABLE parameter is set to 1.

You had terrain_enable set to 1 in your log that I reference where you are unable to download terrain data.

1 Like

Ah! Guilty I am then! Sorry.

I will disable it and do some flight testing next week.

Yes, you must be in GUIDED to get POSITION_TARGET_LOCAL messages.
POSITION_TARGET_GLOBAL_INT is available in other modes RTL (all submodes but Landing), Smart_RTL (similar to landing), Auto, Follow, and Guided (when in WP mode, Pos control mode)

Have you tried using your code in SITL?? That is what I would do next.

1 Like

Iā€™ve never used SITL before but Iā€™ll give it a try.

Okay, I did some more flying today and it seems that MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT must be explicitly requested. At least that is what I am seeing in GUIDED mode. I do get the message when I ask for it. :smiley:

I am potentially seeing a discrepancy in the position target fields vs what I request. This may be an issue with float truncation maybe. Iā€™m not sure yet.

Okay, I found the problem. I was requesting a position target of x,y,z and also yaw. BUT:

POSITION_TARGET_GLOBAL_INT does not return the yaw. In my situation for example, it sets the type mask to:

MAVLINK_MSG_SET_POSITION_TARGET_POSITION |
MAVLINK_MSG_SET_POSITION_TARGET_VELOCITY |
MAVLINK_MSG_SET_POSITION_TARGET_YAW_ANGLE |
MAVLINK_MSG_SET_POSITION_TARGET_YAW_RATE

but it only tells you the x, y, z. IMO this is a bug. Should I raise an issue do you think?

Yeah that it partly what my PR above is trying to address in regards to the reporting in guided mode. *Though i still have to add the yaw bit though that shouldnā€™t be too bad.)

Right now the output from the message is quite limited.

I think there is an issue for it somewhere just having trouble finding it.

1 Like

I have recently discovered what appears to be a small bug with the Arducopter POSITION_TARGET code.

With SITL, if I set a position target with SET_POSITION_TARGET_POSITION of:
6193715 -23766382 20.360001
lat_int lon_int alt
int32 int32 float

I receive a POSITION_TARGET_GLOBAL_INT message with:
6193716 -23766381 20.359999

Something in Arducopter is slightly corrupting these values. Using a real drone, I see a difference as follows:

Was looking for 2897889 57051 29.790001
but saw 2897889 57051 29.789999

I am investigating why this happens and hopefully Iā€™ll find the bug.

I submitted an issue here for anyone reading:

https://github.com/ArduPilot/ardupilot/issues/19607