1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-01 09:24:10 +01:00

Merge remote-tracking branch 'remotes/origin/next' into sambas/diffnext

Conflicts:
	flight/modules/VtolPathFollower/vtolpathfollower.c
This commit is contained in:
sambas 2013-04-28 09:46:14 +03:00
commit 38d9d5dde3
4 changed files with 2887 additions and 2886 deletions

View File

@ -479,14 +479,14 @@ void updateEndpointVelocity()
GPSPositionGet(&gpsPosition);
HomeLocationData homeLocation;
HomeLocationGet(&homeLocation);
float lat = DEG2RAD(homeLocation.Latitude / 10.0e6f);
float lat = DEG2RAD(homeLocation.Latitude / 10.0e6f);
float alt = homeLocation.Altitude;
float T[3] =
{ alt + 6.378137E6f, cosf(lat) * (alt + 6.378137E6f), -1.0f };
float NED[3] =
{ T[0] * (DEG2RAD((gpsPosition.Latitude - homeLocation.Latitude) / 10.0e6f)), T[1]
* (DEG2RAD((gpsPosition.Longitude - homeLocation.Longitude) / 10.0e6f)), T[2]
* ((gpsPosition.Altitude + gpsPosition.GeoidSeparation - homeLocation.Altitude)) };
float T[3] = { alt+6.378137E6f,
cosf(lat)*(alt+6.378137E6f),
-1.0f};
float NED[3] = {T[0] * (DEG2RAD((gpsPosition.Latitude - homeLocation.Latitude) / 10.0e6f)),
T[1] * (DEG2RAD((gpsPosition.Longitude - homeLocation.Longitude) / 10.0e6f)),
T[2] * ((gpsPosition.Altitude + gpsPosition.GeoidSeparation - homeLocation.Altitude))};
northPos = NED[0];
eastPos = NED[1];
@ -608,8 +608,8 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
{
GPSPositionData gpsPosition;
GPSPositionGet(&gpsPosition);
northVel = gpsPosition.Groundspeed * cosf(DEG2RAD(gpsPosition.Heading));
eastVel = gpsPosition.Groundspeed * sinf(DEG2RAD(gpsPosition.Heading));
northVel = gpsPosition.Groundspeed * cosf(DEG2RAD(gpsPosition.Heading));
eastVel = gpsPosition.Groundspeed * sinf(DEG2RAD(gpsPosition.Heading));
downVel = velocityActual.Down;
}
break;
@ -654,9 +654,11 @@ static void updateVtolDesiredAttitude(bool yaw_attitude)
// Project the north and east command signals into the pitch and roll based on yaw. For this to behave well the
// craft should move similarly for 5 deg roll versus 5 deg pitch
stabDesired.Pitch = bound(-northCommand * cosf(DEG2RAD(attitudeActual.Yaw)) + -eastCommand * sinf(DEG2RAD(attitudeActual.Yaw)),
stabDesired.Pitch = bound(-northCommand * cosf(DEG2RAD(attitudeActual.Yaw)) +
-eastCommand * sinf(DEG2RAD(attitudeActual.Yaw)),
-vtolpathfollowerSettings.MaxRollPitch, vtolpathfollowerSettings.MaxRollPitch);
stabDesired.Roll = bound(-northCommand * sinf(DEG2RAD(attitudeActual.Yaw)) + eastCommand * cosf(DEG2RAD(attitudeActual.Yaw)),
stabDesired.Roll = bound(-northCommand * sinf(DEG2RAD(attitudeActual.Yaw)) +
eastCommand * cosf(DEG2RAD(attitudeActual.Yaw)),
-vtolpathfollowerSettings.MaxRollPitch, vtolpathfollowerSettings.MaxRollPitch);
if (vtolpathfollowerSettings.ThrottleControl == VTOLPATHFOLLOWERSETTINGS_THROTTLECONTROL_FALSE) {

View File

@ -2745,13 +2745,12 @@
<showToolbars>false</showToolbars>
<splitter>
<side0>
<side0>
<classId>HITL</classId>
<gadget>
<activeConfiguration>XPlane HITL</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<classId>HITL</classId>
<gadget>
<activeConfiguration>XPlane HITL</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>HITLv2</classId>
<gadget>

View File

@ -51,7 +51,7 @@
</font>
</property>
<property name="text">
<string>#1: Magnetometer calibrtion</string>
<string>#1: Magnetometer calibration</string>
</property>
</widget>
</item>

View File

@ -5,7 +5,7 @@
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="40" limits="%BE:0:180"/>
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="40" limits="%BE:0:180"/>
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,175" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,50" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>