Skip to content

Commit

Permalink
support MAV_CMD_EXTERNAL_WIND_ESTIMATE with autotest
Browse files Browse the repository at this point in the history
  • Loading branch information
python36 committed Aug 28, 2024
1 parent c57caf4 commit 5bb78b9
Show file tree
Hide file tree
Showing 5 changed files with 49 additions and 12 deletions.
41 changes: 41 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -6052,6 +6052,46 @@ def ForceArm(self):
)
self.disarm_vehicle()

def _MAV_CMD_EXTERNAL_WIND_ESTIMATE(self, command):
cmp_with_variance = lambda a, b, p: abs(a - b) < p

self.set_parameters({
"SIM_WIND_SPD": 0,
"SIM_WIND_DIR": 180,
})

m = self.assert_receive_message("WIND")
start_speed = m.speed
start_direction = m.direction

def check_eq(speed, direction, ret_dir):
command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=speed, p3=direction)
for i in range(10):
m = self.assert_receive_message("WIND")

if cmp_with_variance(m.speed, speed, 0.5) and cmp_with_variance(m.direction, ret_dir, 5):
break
else:
raise NotAchievedException("Wind is not equal to given values {} != {} or {} != {}".format(
m.speed, speed, m.direction, ret_dir))

check_eq(1, 45, 45)
check_eq(2, 90, 90)
check_eq(3, 120, 120)
check_eq(4, 180, -180)
check_eq(5, 240, -120)
check_eq(6, 320, -40)
check_eq(7, 360, 0)

command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=-2, p3=90, want_result=mavutil.mavlink.MAV_RESULT_DENIED)
command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=2, p3=-90, want_result=mavutil.mavlink.MAV_RESULT_DENIED)
command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=-2, p3=-90, want_result=mavutil.mavlink.MAV_RESULT_DENIED)

def MAV_CMD_EXTERNAL_WIND_ESTIMATE(self):
'''test _MAV_CMD_EXTERNAL_WIND_ESTIMATE as a mavlink command'''
self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd)
self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd_int)

def tests(self):
'''return list of all tests'''
ret = super(AutoTestPlane, self).tests()
Expand Down Expand Up @@ -6183,6 +6223,7 @@ def tests(self):
self.GPSPreArms,
self.SetHomeAltChange,
self.ForceArm,
self.MAV_CMD_EXTERNAL_WIND_ESTIMATE,
])
return ret

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS.h
Original file line number Diff line number Diff line change
Expand Up @@ -132,8 +132,8 @@ class AP_AHRS {
}

#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
void external_wind_estimate(float speed, float direction) {
dcm.external_wind_estimate(speed, direction);
void set_external_wind_estimate(float speed, float direction) {
dcm.set_external_wind_estimate(speed, direction);
}
#endif

Expand Down
12 changes: 4 additions & 8 deletions libraries/AP_AHRS/AP_AHRS_DCM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1029,14 +1029,10 @@ void AP_AHRS_DCM::estimate_wind(void)
}

#ifdef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
void AP_AHRS_DCM::external_wind_estimate(float speed, float direction) {
Vector3f wind = Vector3f();
wind.z = 0;

wind.x = -cosf(radians(direction)) * speed;
wind.y = -sinf(radians(direction)) * speed;

_wind = wind;
void AP_AHRS_DCM::set_external_wind_estimate(float speed, float direction) {
_wind.x = -cosf(radians(direction)) * speed;
_wind.y = -sinf(radians(direction)) * speed;
_wind.z = 0;
}
#endif

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_AHRS/AP_AHRS_DCM.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class AP_AHRS_DCM : public AP_AHRS_Backend {
return true;
}

void external_wind_estimate(float speed, float direction);
void set_external_wind_estimate(float speed, float direction);

// return an airspeed estimate if available. return true
// if we have an estimate
Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5243,7 +5243,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_external_wind_estimate(const mavlink_
return MAV_RESULT_DENIED;
}

AP::ahrs().external_wind_estimate(packet.param1, packet.param3);
AP::ahrs().set_external_wind_estimate(packet.param1, packet.param3);
return MAV_RESULT_ACCEPTED;
}
#endif // AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
Expand Down

0 comments on commit 5bb78b9

Please sign in to comment.