public MAV_MISSION_RESULT setWP(Locationwp loc, ushort index, MAV_FRAME frame, byte current = 0,
byte autocontinue = 1, bool use_int = false)
{
if (use_int)
{
mavlink_mission_item_int_t req = new mavlink_mission_item_int_t();
req.target_system = MAV.sysid;
req.target_component = MAV.compid;
req.command = loc.id;
req.current = current;
req.autocontinue = autocontinue;
req.frame = (byte) frame;
if (loc.id == (ushort)MAV_CMD.DO_DIGICAM_CONTROL || loc.id == (ushort)MAV_CMD.DO_DIGICAM_CONFIGURE)
{
req.y = (int)(loc.lng);
req.x = (int)(loc.lat);
}
else
{
req.y = (int)(loc.lng * 1.0e7);
req.x = (int)(loc.lat * 1.0e7);
}
req.z = (float) (loc.alt);
req.param1 = loc.p1;
req.param2 = loc.p2;
req.param3 = loc.p3;
req.param4 = loc.p4;
req.seq = index;
return setWP(req);
}
else
{
mavlink_mission_item_t req = new mavlink_mission_item_t();
req.target_system = MAV.sysid;
req.target_component = MAV.compid;
req.command = loc.id;
req.current = current;
req.autocontinue = autocontinue;
req.frame = (byte)frame;
req.y = (float)(loc.lng);
req.x = (float)(loc.lat);
req.z = (float)(loc.alt);
req.param1 = loc.p1;
req.param2 = loc.p2;
req.param3 = loc.p3;
req.param4 = loc.p4;
req.seq = index;
return setWP(req);
}
}