[GUIDED ISSUE] Copter doesn't want to change height if I don't set also latitude and longitude

Hello,

I think I’m facing a small issue in GUIDED mode.
When I send a mavlink message “set_position_target_global_int” with only an ordre to change the height in MAV_FRAME_GLOBAL_RELATIVE_ALT_INT frame, nothing happens. I need to send also a position in latitude and longitude.

This is the code that soesn’t work

msg_set_position_target_global_int gotoPos = new msg_set_position_target_global_int();
		gotoPos.compid = compId;
		gotoPos.sysid = sysId;
		gotoPos.target_component = (short) targetCompId;
		gotoPos.target_system = (short) targetSysId;
		gotoPos.time_boot_ms = System.currentTimeMillis() - timeStart;
		gotoPos.alt = (float) (((float) height)/100.0);
		gotoPos.coordinate_frame = MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT;
		gotoPos.type_mask = POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_AX_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_AY_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_AZ_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_VX_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_VY_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_VZ_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_X_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_Y_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_YAW_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE;
		
		sendMessage(sysId, compId, gotoPos);

And with this code that works

msg_set_position_target_global_int gotoPos = new msg_set_position_target_global_int();
		gotoPos.compid = compId;
		gotoPos.sysid = sysId;
		gotoPos.target_component = (short) targetCompId;
		gotoPos.target_system = (short) targetSysId;
		gotoPos.time_boot_ms = System.currentTimeMillis() - timeStart;
		gotoPos.alt = (float)  pos.getAltitude();
		gotoPos.lat_int = (int) (pos.getLatitude() * 10000000);
		gotoPos.lon_int = (int) (pos.getLongitude() * 10000000);
		gotoPos.coordinate_frame = MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT;
		gotoPos.type_mask = POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_AX_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_AY_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_AZ_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_VX_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_VY_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_VZ_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_YAW_IGNORE
				+ POSITION_TARGET_TYPEMASK.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE;
		
		sendMessage(sysId, compId, gotoPos);

I don’t think that your TYPEMASK is valid.

Looking at the Arducopter source it only accepts things like MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE so your wish to just set altitude does not look possible to me.

I could be wrong though as I am not an expert with the source code.

In fact the values are defined here : Messages (common) · MAVLink Developer Guide

But I can’t find MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE

Indeed, it seems that it’s not possible to simply modify the altitude without set a position in GUIDED mode

Yes, that’s right, Copter doesn’t support providing only the target altitude when using SET_POSITION_TARGET_GLOBAL_INT (or the similar LOCAL_NED). I’ve created an enhancement request here but of course, no promises on when it might be implemented.

1 Like

I will take a look at it when I am available.

2 Likes

Thanks, for the moment I send 2 Mavlink order, the first to get altitude (with current GNSS Position) and the second one with the target Waypoint.
But I didn’t find any way to change only height of flight in guided mode and it lacks

Proper change would also bring the support for Messages (common) · MAVLink Developer Guide
and all the MAV_CMD_GUIDED_CHANGE_* set : ardupilotmega.xml · MAVLink Developer Guide

Not a hard work. @Dronotique wanna do a PR ?

In fact MAV_CMD_DO_CHANGE_ALTITUDE allow only to change Altitude and not the height… I think also this Mavlink message lacks a FRAME parameter!

I would love to!!!
I checked the code, but I’m a little bit lost in it. I’m not really a C++ developper!
I started to check the code and I saw ModeGuided::set_destination but I don’t really understand how it works