Subversion Repositories Projects

Rev

Rev 1562 | Go to most recent revision | Blame | Compare with Previous | Last modification | View Log | RSS feed

package dongfang.mkt.frames;

public class OSDDataResponseFrame extends ResponseFrame {

        public static class GPSPosition {
                int longitude; // in 1E-7 degrees. 32 bit signed.
                int latitude;  // in 1E-7 degrees. 32 bit signed.
                long altitude;  // in mm. 32 bit signed.
                int status;
                public int getLongitude() {
                        return longitude;
                }
                public int getLatitude() {
                        return latitude;
                }
                public long getAltitude() {
                        return altitude;
                }
                public int getStatus() {
                        return status;
                }
                public void setLongitude(int longitude) {
                        this.longitude = longitude;
                }
                public void setLatitude(int latitude) {
                        this.latitude = latitude;
                }
                public void setAltitude(long altitude) {
                        this.altitude = altitude;
                }
                public void setStatus(int status) {
                        this.status = status;
                }
        }
       
        public static class GPSDistanceAndBearing {
                int distance;   // in m/10. 16 bit unsigned.
                int bearing;    // in degrees. 16 bit signed.
                public int getDistance() {
                        return distance;
                }
                public int getBearing() {
                        return bearing;
                }
                public void setDistance(int distance) {
                        this.distance = distance;
                }
                public void setBearing(int bearing) {
                        this.bearing = bearing;
                }
        }

        private int version;
        private GPSPosition currentPosition;
        private GPSPosition targetPosition;
        private GPSDistanceAndBearing currentToTarget;
        private GPSPosition homePosition;
        private GPSDistanceAndBearing currentToHome;
       
        private int waypointIndex;
        private int waypointCount;
       
        private int numberOfSatellites;
        private int heightByPressure;           // 16 bit signed.
        private int verticalVelocityByPressure; // 16 bit signed.
       
        private int flightTime; // in secs. 16 bit unsigned.
        private int batteryVoltage; // in 0.1 volts.

        private int groundSpeed; // in cm/s. 16 bit unsigned.
        private int heading;     // 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 int verticalVelocityByGPS;      // 16 bit signed.
       
        private int targetLoiterTime;
        private int fcFlags2;
        private int setpointForAltitude;        // 16 bit signed.
       
        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 GPSDistanceAndBearing getCurrentToTarget() {
                return currentToTarget;
        }
        public GPSPosition getHomePosition() {
                return homePosition;
        }
        public GPSDistanceAndBearing getCurrentToHome() {
                return currentToHome;
        }
        public int getWaypointIndex() {
                return waypointIndex;
        }
        public int getWaypointCount() {
                return waypointCount;
        }
        public int getNumberOfSatellites() {
                return numberOfSatellites;
        }
        public int getHeightByPressure() {
                return heightByPressure;
        }
        public int getVerticalVelocityByPressure() {
                return verticalVelocityByPressure;
        }
        public int getFlightTime() {
                return flightTime;
        }
        public int getBatteryVoltage() {
                return batteryVoltage;
        }
        public int getGroundSpeed() {
                return groundSpeed;
        }
        public int getHeading() {
                return heading;
        }
        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 int getVerticalVelocityByGPS() {
                return verticalVelocityByGPS;
        }
        public int getTargetLoiterTime() {
                return targetLoiterTime;
        }
        public int getFcFlags2() {
                return fcFlags2;
        }
        public int 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(GPSDistanceAndBearing currentToTarget) {
                this.currentToTarget = currentToTarget;
        }
        public void setHomePosition(GPSPosition homePosition) {
                this.homePosition = homePosition;
        }
        public void setCurrentToHome(GPSDistanceAndBearing 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(int heightByPressure) {
                this.heightByPressure = heightByPressure;
        }
        public void setVerticalVelocityByPressure(int verticalVelocityByPressure) {
                this.verticalVelocityByPressure = verticalVelocityByPressure;
        }
        public void setFlightTime(int flightTime) {
                this.flightTime = flightTime;
        }
        public void setBatteryVoltage(int batteryVoltage) {
                this.batteryVoltage = batteryVoltage;
        }
        public void setGroundSpeed(int groundSpeed) {
                this.groundSpeed = groundSpeed;
        }
        public void setHeading(int heading) {
                this.heading = 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(int verticalVelocityByGPS) {
                this.verticalVelocityByGPS = verticalVelocityByGPS;
        }
        public void setTargetLoiterTime(int targetLoiterTime) {
                this.targetLoiterTime = targetLoiterTime;
        }
        public void setFcFlags2(int fcFlags2) {
                this.fcFlags2 = fcFlags2;
        }
        public void setSetpointForAltitude(int 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;
        }
}