Working on memory problem.
This commit is contained in:
parent
937a268513
commit
60b41311f0
@ -96,15 +96,11 @@ private:
|
|||||||
float cmdDown = pidPD.update(_nav->getPD(),_nav->getVD(),dt);
|
float cmdDown = pidPD.update(_nav->getPD(),_nav->getVD(),dt);
|
||||||
|
|
||||||
// "transform-to-body"
|
// "transform-to-body"
|
||||||
{
|
_cmdPitch = cmdNorthTilt * cos(_nav->getYaw()) + cmdEastTilt * sin(_nav->getYaw());
|
||||||
float trigSin = sin(-_nav->getYaw());
|
_cmdRoll = -cmdNorthTilt * sin(_nav->getYaw()) + cmdEastTilt * cos(_nav->getYaw());
|
||||||
float trigCos = cos(-_nav->getYaw());
|
_cmdPitch *= -1; // note that the north tilt is negative of the pitch
|
||||||
_cmdPitch = cmdEastTilt * trigCos - cmdNorthTilt * trigSin;
|
|
||||||
_cmdRoll = -cmdEastTilt * trigSin + cmdNorthTilt * trigCos;
|
|
||||||
// note that the north tilt is negative of the pitch
|
|
||||||
}
|
|
||||||
_cmdYawRate = 0;
|
|
||||||
|
|
||||||
|
_cmdYawRate = 0;
|
||||||
_thrustMix = THRUST_HOVER_OFFSET + cmdDown;
|
_thrustMix = THRUST_HOVER_OFFSET + cmdDown;
|
||||||
|
|
||||||
// "thrust-trim-adjust"
|
// "thrust-trim-adjust"
|
||||||
|
@ -460,7 +460,7 @@ function(setup_arduino_upload BOARD_ID TARGET_NAME PORT)
|
|||||||
-p${${BOARD_ID}.build.mcu}
|
-p${${BOARD_ID}.build.mcu}
|
||||||
-c${${BOARD_ID}.upload.protocol}
|
-c${${BOARD_ID}.upload.protocol}
|
||||||
-P${PORT} -b${${BOARD_ID}.upload.speed}
|
-P${PORT} -b${${BOARD_ID}.upload.speed}
|
||||||
-D
|
#-D
|
||||||
-Uflash:w:${CMAKE_BINARY_DIR}/${TARGET_NAME}.hex:i
|
-Uflash:w:${CMAKE_BINARY_DIR}/${TARGET_NAME}.hex:i
|
||||||
DEPENDS ${TARGET_NAME})
|
DEPENDS ${TARGET_NAME})
|
||||||
if(NOT TARGET upload)
|
if(NOT TARGET upload)
|
||||||
|
@ -62,8 +62,8 @@ AP_MavlinkCommand::AP_MavlinkCommand(const mavlink_waypoint_t & cmd) :
|
|||||||
setZ(cmd.z);
|
setZ(cmd.z);
|
||||||
save();
|
save();
|
||||||
|
|
||||||
// reload home if sent
|
// reload home if sent, home must be a global waypoint
|
||||||
if (cmd.seq == 0) home.load();
|
if ( (cmd.seq == 0) && (cmd.frame == MAV_FRAME_GLOBAL)) home.load();
|
||||||
|
|
||||||
Serial.println("============================================================");
|
Serial.println("============================================================");
|
||||||
Serial.println("storing new command from mavlink_waypoint_t");
|
Serial.println("storing new command from mavlink_waypoint_t");
|
||||||
|
Loading…
Reference in New Issue
Block a user