Quadcopter climbs constantly in Offboard mode

Hi!
Nowadays I’m trying to control copter from QGroundControl in Offboard mode. For this purpose I use SET_POSITION_TARGET_LOCAL_NED messages with bitmask
(0xFFF8 & (~(1<<10)) ),
controlling x,y,z and yaw.

I extract WGS target position from Flight Map and convert it to local XYZ coordinates. For this purpose I must know global position of local frame. I extract it from HOME_POSITION message. Debug output shows something like:

Home set: lat  60.0222  	lon  20.3682  	alt  14.622
Home local coords:  x 6.86949   y -1.21904   z 0.143501
Local frame global coords:   lat 60.0221   lon 20.3682   alt 14.4785

and this seems to be Ok.
Know when I know WGS coordinates of local frame I can take WGS target point, convert to local XYZ and pass into Flight controller.
It works fine in JMavSim. Copter flies to location on which I clicked. But suddenly when I go to Offboard after Takeoff on real copter it starts to gain height constantly whereas I pass exactly local z that was in time of mode switching. Copter follows target x and y but doesn’t seem that z is interpreted in a right way.

Well, I said, let’s check what if I gave zero height instead of current z. The same reaction…
Well, I said then, let us change bitmask to
(0xFFFC & (~(1<<10)) ),
so only x, y and yaw are controlled, without z.
When I checked this in simulator, copter flew in a strange way, so I didn’t try it in live.

And this became now a problem for me. I checked what I get in LOCAL_POSITION_NED packets - and it’s Ok, copter answers with a growing relative altitude as well. I got stuck.

P.S. Onboard I have PixFalcon and Intel Joule with mavros.
Not expecting for deep help, but anyway, maybe someone has suggestions.

UPD. About controlling x,y and yaw without z. What I found going through px4 Firmware.
Function handle_message_set_position_target_local_ned in mavlink_receiver.cpp:

offboard_control_mode.ignore_position = (bool)(set_position_target_local_ned.type_mask & 0x7)

that means that if z is masked whereas x and y are not, flag ignore_position is set in any case - no position control at all. At the same time there is another flag:

offboard_control_mode.ignore_alt_hold = (bool)(set_position_target_local_ned.type_mask & 0x4)

that checks separately if z is masked in command.
So my next step will be changing ignore_position to
offboard_control_mode.ignore_position = (bool)(set_position_target_local_ned.type_mask & 0x3)
trying control still x and y. Might it work?
And why masking z position control must cancel xy position control corresponding to logic of developers?