package dongfang.mkt.frames;
import dongfang.mkt.datatype.GPSBearingAndRange;
import dongfang.mkt.datatype.GPSPosition;
public class OSDDataResponseFrame
extends ResponseFrame
{
private int version
;
private GPSPosition currentPosition
;
private GPSPosition targetPosition
;
private GPSBearingAndRange currentToTarget
;
private GPSPosition homePosition
;
private GPSBearingAndRange currentToHome
;
private int waypointIndex
;
private int waypointCount
;
private int numberOfSatellites
;
private double heightByPressure
; // in m.
private double verticalVelocityByPressure
; // 16 bit signed.
private int flightTime
; // in secs. 16 bit unsigned.
private int batteryVoltage
; // in 0.1 volts.
private double groundSpeed
; // in m/s. 16 bit unsigned.
private int directionOfFlight
; // of movement. 16 bit signed.
private int compassHeading
;// 16 bit signed.
private int pitchAngle
;
private int rollAngle
;
private int rcQuality
;
private int fcFlags
;
private int ncFlags
;
private int errorCode
;
private int operatingRadius
;
private double verticalVelocityByGPS
; // 16 bit signed.
private int targetLoiterTime
;
private int fcFlags2
;
private double setpointForAltitude
; // in m.
private int throttle
;
private int current
; // 16 bit unsigned.
private int capacityUsed
; // 16 bit unsigned.
public OSDDataResponseFrame
(int address
) {
super(address
);
}
public int getVersion
() {
return version
;
}
public GPSPosition getCurrentPosition
() {
return currentPosition
;
}
public GPSPosition getTargetPosition
() {
return targetPosition
;
}
public GPSBearingAndRange getCurrentToTarget
() {
return currentToTarget
;
}
public GPSPosition getHomePosition
() {
return homePosition
;
}
public GPSBearingAndRange getCurrentToHome
() {
return currentToHome
;
}
public int getWaypointIndex
() {
return waypointIndex
;
}
public int getWaypointCount
() {
return waypointCount
;
}
public int getNumberOfSatellites
() {
return numberOfSatellites
;
}
public double getHeightByPressure
() {
return heightByPressure
;
}
public double getVerticalVelocityByPressure
() {
return verticalVelocityByPressure
;
}
public int getFlightTime
() {
return flightTime
;
}
public int getBatteryVoltage
() {
return batteryVoltage
;
}
public double getGroundSpeed
() {
return groundSpeed
;
}
public int getDirectionOfFlight
() {
return directionOfFlight
;
}
public int getCompassHeading
() {
return compassHeading
;
}
public int getPitchAngle
() {
return pitchAngle
;
}
public int getRollAngle
() {
return rollAngle
;
}
public int getRcQuality
() {
return rcQuality
;
}
public int getFcFlags
() {
return fcFlags
;
}
public int getNcFlags
() {
return ncFlags
;
}
public int getErrorCode
() {
return errorCode
;
}
public int getOperatingRadius
() {
return operatingRadius
;
}
public double getVerticalVelocityByGPS
() {
return verticalVelocityByGPS
;
}
public int getTargetLoiterTime
() {
return targetLoiterTime
;
}
public int getFcFlags2
() {
return fcFlags2
;
}
public double getSetpointForAltitude
() {
return setpointForAltitude
;
}
public int getThrottle
() {
return throttle
;
}
public int getCurrent
() {
return current
;
}
public int getCapacityUsed
() {
return capacityUsed
;
}
public void setVersion
(int version
) {
this.
version = version
;
}
public void setCurrentPosition
(GPSPosition currentPosition
) {
this.
currentPosition = currentPosition
;
}
public void setTargetPosition
(GPSPosition targetPosition
) {
this.
targetPosition = targetPosition
;
}
public void setCurrentToTarget
(GPSBearingAndRange currentToTarget
) {
this.
currentToTarget = currentToTarget
;
}
public void setHomePosition
(GPSPosition homePosition
) {
this.
homePosition = homePosition
;
}
public void setCurrentToHome
(GPSBearingAndRange currentToHome
) {
this.
currentToHome = currentToHome
;
}
public void setWaypointIndex
(int waypointIndex
) {
this.
waypointIndex = waypointIndex
;
}
public void setWaypointCount
(int waypointCount
) {
this.
waypointCount = waypointCount
;
}
public void setNumberOfSatellites
(int numberOfSatellites
) {
this.
numberOfSatellites = numberOfSatellites
;
}
public void _setHeightByPressure
(double heightByPressure
) {
this.
heightByPressure = heightByPressure
;
}
public void setVerticalVelocityByPressure
(double verticalVelocityByPressure
) {
this.
verticalVelocityByPressure = verticalVelocityByPressure
;
}
public void setFlightTime
(int flightTime
) {
this.
flightTime = flightTime
;
}
public void setBatteryVoltage
(int batteryVoltage
) {
this.
batteryVoltage = batteryVoltage
;
}
public void setGroundSpeed
(double groundSpeed
) {
this.
groundSpeed = groundSpeed
;
}
public void setDirectionOfFlight
(int heading
) {
this.
directionOfFlight = heading
;
}
public void setCompassHeading
(int compassHeading
) {
this.
compassHeading = compassHeading
;
}
public void setPitchAngle
(int pitchAngle
) {
this.
pitchAngle = pitchAngle
;
}
public void setRollAngle
(int rollAngle
) {
this.
rollAngle = rollAngle
;
}
public void setRcQuality
(int rcQuality
) {
this.
rcQuality = rcQuality
;
}
public void setFcFlags
(int fcFlags
) {
this.
fcFlags = fcFlags
;
}
public void setNcFlags
(int ncFlags
) {
this.
ncFlags = ncFlags
;
}
public void setErrorCode
(int errorCode
) {
this.
errorCode = errorCode
;
}
public void setOperatingRadius
(int operatingRadius
) {
this.
operatingRadius = operatingRadius
;
}
public void setVerticalVelocityByGPS
(double verticalVelocityByGPS
) {
this.
verticalVelocityByGPS = verticalVelocityByGPS
;
}
public void setTargetLoiterTime
(int targetLoiterTime
) {
this.
targetLoiterTime = targetLoiterTime
;
}
public void setFcFlags2
(int fcFlags2
) {
this.
fcFlags2 = fcFlags2
;
}
public void setSetpointForAltitude
(double setpointForAltitude
) {
this.
setpointForAltitude = setpointForAltitude
;
}
public void setThrottle
(int throttle
) {
this.
throttle = throttle
;
}
public void setCurrent
(int current
) {
this.
current = current
;
}
public void setCapacityUsed
(int capacityUsed
) {
this.
capacityUsed = capacityUsed
;
}
@
Override
public boolean isResponseTo
(RequestFrame r
) {
return r
instanceof OSDDataRequestFrame
;
}
public String toString
() {
StringBuilder result =
new StringBuilder();
result.
append("OSDData version=" +
this.
version +
"\n");
result.
append("currentPosition: " +
this.
currentPosition +
"\n");
result.
append("targetPosition: " +
this.
targetPosition +
" (" +
this.
currentToTarget +
")" +
"\n");
result.
append("homePosition: " +
this.
homePosition +
" (" +
this.
currentToHome +
")" +
"\n");
result.
append("heightByPressure: " +
this.
heightByPressure +
"\n");
result.
append("heightByPressureReal: " +
this.
heightByPressure /
1.26 +
"\n");
result.
append("verticalVelocityByPressure: " +
this.
verticalVelocityByPressure +
"\n");
result.
append("verticalVelocityByGPS: " +
this.
verticalVelocityByGPS +
"\n");
result.
append("direction of flight: " +
this.
directionOfFlight +
"\n");
result.
append("compassHeading: " +
this.
compassHeading +
"\n");
result.
append("pitchAngle: " +
this.
pitchAngle +
"\n");
result.
append("rollAngle: " +
this.
rollAngle +
"\n");
result.
append("battery voltage: " +
((double)this.
batteryVoltage)/
10 +
"\n");
result.
append("throttle: " +
this.
throttle +
"\n");
return result.
toString();
}
}