/// <summary> /// Used for non ardupilot params that use the defined type /// </summary> /// <param name="name"></param> /// <param name="inputwire"></param> /// <param name="type"></param> public MAVLinkParam(string name, float inputwire, MAV_PARAM_TYPE type) { Name = name; Type = type; data = BitConverter.GetBytes(inputwire); Array.Resize(ref data, 4); }
public MAVLinkParam(string name, byte[] inputwire, MAV_PARAM_TYPE type) { Name = name; Type = type; data = inputwire; Array.Resize(ref data, 4); }
/// <summary> /// Used to set Ardupilot Params /// </summary> /// <param name="name"></param> /// <param name="inputwire"></param> /// <param name="wiretype"></param> /// <param name="typeap"></param> public MAVLinkParam(string name, byte[] inputwire, MAV_PARAM_TYPE wiretype, MAV_PARAM_TYPE typeap) { Name = name; Type = wiretype; TypeAP = typeap; Array.Copy(inputwire, _data, 4); }
public MAVLinkParam(string name, float inputwire, MAV_PARAM_TYPE type) { Name = name; Type = type; data = BitConverter.GetBytes(inputwire); Array.Resize(ref data, 4); }
/// <summary> /// used as a generic input to type the input data /// </summary> /// <param name="name"></param> /// <param name="value"></param> /// <param name="type"></param> public MAVLinkParam(string name, double value, MAV_PARAM_TYPE type) { Name = name; Type = type; Value = value; }
public MAVLinkParam(string name, double value, MAV_PARAM_TYPE type) { Name = name; Type = type; Value = value; }
/// <summary> /// Used to set Ardupilot Params /// </summary> /// <param name="name"></param> /// <param name="inputwire"></param> /// <param name="type"></param> /// <param name="typeap"></param> public MAVLinkParam(string name, byte[] inputwire, MAV_PARAM_TYPE type, MAV_PARAM_TYPE typeap) { Name = name; Type = type; TypeAP = typeap; Array.Copy(inputwire, _data, 4); }