Position and Velocity control with SET_POSITION_TARGET_GLOBAL_INT

Dear ardupilot community,

Thank you all for your amazing work.
I have a new question for you and I thank you in advance for any help.

I want to be able to set a target position on Lat, Lon coordinates while at the same time control the altitude with velocity.
I’ve managed to control the position and the Z-velocity separatly but I’m not sure on how I should do this together.
I have tried to set a Lat, Lon position with a x and y-velocity to zero but in this case the drone doesn’t move in the xy direction:

mli.SendSetPositionTargetGlobalInt(0, 5, 0b0000111111111111, D_Lat, D_Lon, alt, 0, 0, -1, 0, 0, 0, 0, 0);

I have also tried to first set the position and then play with the velocity (still with x and y velocity to zero) but the moment I send the second command, the desired position is updated to the actual position (which isn’t exactly D_Lat and D_Lon):

1: mli.SendSetPositionTargetGlobalInt(0, 5, 0b0000111111111000, D_Lat, D_Lon, alt, 0, 0, 0, 0, 0, 0, 0, 0);
2: mli.SendSetPositionTargetGlobalInt(0, 5, 0b0000111111000111, D_Lat, D_Lon, alt, 0, 0, -1, 0, 0, 0, 0, 0);

Does anyone know if there is a way to do this ?
I’ll continue digging into the source code but if there is already someone with an answer somewhere it will help me a lot.

Thanks again,

Regards.

1 Like

Hi Thomas,
Thanks for using ArduPilot.
So at the moment, we only support 3 combinations of the bitmask:

  • velocity control (3d)
  • position control (3d)
  • position + velocity (i.e. send in a consistent set of both and it will try and achieve both).

The relevant bits of the code are here:
GCS_Mavlink.cpp is where we consume the set-position-target message: https://github.com/ArduPilot/ardupilot/blob/master/ArduCopter/GCS_Mavlink.cpp#L1688
control_guided.cpp is where Guided mode exposes it’s controls: https://github.com/ArduPilot/ardupilot/blob/master/ArduCopter/control_guided.cpp

So I think maybe the best you could do is send in the position + velocity and just make sure that you keep updating the target altitude with an altitude that is consistent with the velocity vector you’ve provided.

1 Like

Hi rmackay9,

Thank you for your reply.
I have taken a look inside the libraries and I think I am missing something because the drone’s behaviour is not what I expect it to be.

I work with the position + velocity bitmask but I’m not sure what you mean by “a consistent set of both”. What I understood from the source code is that the target position is updated each time with the target velocity (target_position += target_velocity * dt). So, if I want the drone to aim a specific target position I thought that I just needed to set a target position with a null velocity, but when I do this, the target position is set at the current position (and I wasn’t able to find where this happens in the code).

Using just the position bitmask works perfectly but because I want a position control in the x,y direction and a velocity control in the z direction I cannot just use the position bitmask.

Any idea what the best option would be ?

Thanks again for your help,

Regards,

Thomas

2 Likes