OFFBOARD takeoff, land, loiter via SET_POSITION_TARGET_LOCAL_NED

Previously discussed here : Offboard automatic TakeOff / Landing using MAV_CMD_LAND/TAKEOFF_LOCAL - #5 by tdo

From the Mavlink receiver implemented in the PX4 Firmware, we can read that there are undocumented features for the SET_POSITION_TARGET_LOCAL_NED mavlink message.

We can see there are a Takeoff, Land, Loiter and Idle setpoints for Offboard mode.

How far are those implemented? Are those safe to use? What happens if we send a Position and a Velocity setpoint? (by ignoring neither the velocity nor the position)

I tested that enum under Gazebo 7, with PX4 Firmware 1.5.5

enum TypeMasks {
    MASK_POSITION =         0b0000111111111000,
    MASK_VELOCITY =         0b0000111111000111,
    MASK_TAKEOFF_POSITION = 0b0001111111111000,
    MASK_TAKEOFF =          0b0001111111111111,
    MASK_LAND_VELOCITY =    0b0010111111000111,
    MASK_LAND_POSITION =    0b0010111111111000,
    MASK_LAND =             0b0010111111111111,
    MASK_LOITER_POSITION =  0b0100111111111000,
    MASK_IDLE_POSITION =    0b1000111111111000,
};
  • MASK_TAKEOFF_POSITION ; Takeoff and go to the position after
  • MASK_POSITION ; Go to the position
  • MASK_VELOCITY; Apply that speed
  • MASK_LAND_POSITION`; Go to the position with Z=0, GUARANTEED CRASH FOR MULTICOPTER
  • MASK_LAND; Freefall, all motors off, GUARANTEED CRASH FOR ANY VEHICLE
  • MASK_LAND_VELOCITY; Going down, ignoring given Z velocity.
  • Loiter & Idle not tested

For safety, shouldn’t :

  • The MASK_LAND should be understood like MASK_LAND_VELOCITY with (0,0,0) velocities.
  • The *MASK_LAND_POSITION go for the XY position before going down ?

Hello,

I’m still using version 1.4.4 but I will switch to 1.5.5

As I’m landing using Offboard command, i’m using this bitmask : (0x2000 | 0b110111000011). I also set null speed for vx and vy (even if its redundant with bitfield, just to make sure)

nedSetpoint->vx = 0; /* Set Null Speed for x and y translation */
nedSetpoint->vy = 0;

Also as I request landing the first step I do in order to bouild the NED setpoint is to use the actual Local NED for North and East, hence landing vertically.

If I correctly remember, you need to set non Null speed in SET_POSITION_TARGET_LOCAL_NED message.

I’m not sure the MASK_LAND_POSITION is really usefull as the developpers are able to decompose it in two steps. In order to avoid freefall, But having a clear and simple vertical landing procedure in offboard mode will be great :slight_smile:

I don’t use Idle or Loiter (in order to achieve loiter, I continously send SET_POSITION_TARGET_LOCAL_NED message with the exact same North East Down coordonate). I do not know what Idle is intended for.

Hope it helps.

Hi,

Do you mean that if i where OFFBORAD, (e.g Raspberry pi connected to Pixhawk). I should use the following message SET_POSITION_TARGET_LOCAL_NED to take off??

Can I do it simply by using MAV_CMD_NAV_TAKEOFF??

Thanks

In offboard mode the best solution is to use the velocity setpoint.

The AUTO TAKEOFF is a part of the Waypoint system (GPS Waypoints)

Does that code means if we set SET_POSITION_TARGET_LOCAL_NED 's z to 0 it automatically lands untill it reaches ground?

I’m having simillar issue in gazebo & real flight test

in gazebo if I set SET_POSITION_TARGET_LOCAL_NED to 0,0,0 copter free falls

but in real flight if I set SET_POSITION_TARGET_LOCAL_NED to 0,0,0 copter surfes around ground about 5cm and doesn’t lands

I’m looking for other ways to takeoff and land is there?
how does ‘rosrun mavros mavcmd landcur’ work?

My method is to send a velocity setpoint of 0.5m/s up to 1m/s