mirror of https://github.com/ArduPilot/ardupilot
AP_Beacon_Marvelmind: Refactor variables
This commit is contained in:
parent
358b3d222b
commit
64fdefe7cf
|
@ -142,9 +142,9 @@ void AP_Beacon_Marvelmind::process_beacons_positions_datagram()
|
|||
stationary_beacon = get_or_alloc_beacon(address);
|
||||
if (stationary_beacon != nullptr) {
|
||||
stationary_beacon->address = address; //The instance and the address are the same
|
||||
stationary_beacon->x = x * 10; // centimeters -> millimeters
|
||||
stationary_beacon->y = y * 10; // centimeters -> millimeters
|
||||
stationary_beacon->z = z * 10; // centimeters -> millimeters
|
||||
stationary_beacon->x__mm = x * 10; // centimeters -> millimeters
|
||||
stationary_beacon->y__mm = y * 10; // centimeters -> millimeters
|
||||
stationary_beacon->z__mm = z * 10; // centimeters -> millimeters
|
||||
stationary_beacon->high_resolution = false;
|
||||
hedge.positions_beacons.updated = true;
|
||||
}
|
||||
|
@ -177,9 +177,9 @@ void AP_Beacon_Marvelmind::process_beacons_positions_highres_datagram()
|
|||
stationary_beacon = get_or_alloc_beacon(address);
|
||||
if (stationary_beacon != nullptr) {
|
||||
stationary_beacon->address = address; //The instance and the address are the same
|
||||
stationary_beacon->x = x; // millimeters
|
||||
stationary_beacon->y = y; // millimeters
|
||||
stationary_beacon->z = z; // millimeters
|
||||
stationary_beacon->x__mm = x; // millimeters
|
||||
stationary_beacon->y__mm = y; // millimeters
|
||||
stationary_beacon->z__mm = z; // millimeters
|
||||
stationary_beacon->high_resolution = true;
|
||||
hedge.positions_beacons.updated = true;
|
||||
}
|
||||
|
|
|
@ -43,14 +43,14 @@ private:
|
|||
{
|
||||
uint8_t address;
|
||||
uint32_t timestamp;
|
||||
int32_t x, y, z; // coordinates in millimeters
|
||||
int32_t x__mm, y__mm, z__mm;
|
||||
bool high_resolution;
|
||||
};
|
||||
|
||||
struct StationaryBeaconPosition
|
||||
{
|
||||
uint8_t address;
|
||||
int32_t x, y, z;// coordinates in millimeters
|
||||
int32_t x__mm, y__mm, z__mm;
|
||||
bool high_resolution;
|
||||
float distance__m; // Distance between beacon and hedge
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue