mirror of https://github.com/ArduPilot/ardupilot
AR_PosControl: adjust for logging having moved into AC_AttitudeControl
This commit is contained in:
parent
fcbd88558c
commit
d0cc35af3e
|
@ -21,6 +21,7 @@
|
|||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AC_Avoidance/AC_Avoid.h>
|
||||
#include <AC_AttitudeControl/AC_PosControl.h>
|
||||
|
||||
#define AR_POSCON_TIMEOUT_MS 100 // timeout after 0.1 sec
|
||||
#define AR_POSCON_POS_P 0.2f // default position P gain
|
||||
|
@ -385,7 +386,8 @@ void AR_PosControl::write_log()
|
|||
// convert position to required format
|
||||
Vector2f pos_target_2d_cm = get_pos_target().tofloat() * 100.0;
|
||||
|
||||
AP::logger().Write_PSCN(pos_target_2d_cm.x, // position target
|
||||
// reuse logging from AC_PosControl:
|
||||
AC_PosControl::Write_PSCN(pos_target_2d_cm.x, // position target
|
||||
curr_pos_NED.x * 100.0, // position
|
||||
_vel_desired.x * 100.0, // desired velocity
|
||||
_vel_target.x * 100.0, // target velocity
|
||||
|
@ -393,7 +395,7 @@ void AR_PosControl::write_log()
|
|||
_accel_desired.x * 100.0, // desired accel
|
||||
_accel_target.x * 100.0, // target accel
|
||||
curr_accel_NED.x); // accel
|
||||
AP::logger().Write_PSCE(pos_target_2d_cm.y, // position target
|
||||
AC_PosControl::Write_PSCE(pos_target_2d_cm.y, // position target
|
||||
curr_pos_NED.y * 100.0, // position
|
||||
_vel_desired.y * 100.0, // desired velocity
|
||||
_vel_target.y * 100.0, // target velocity
|
||||
|
|
Loading…
Reference in New Issue