Path: blob/master/libraries/AC_AttitudeControl/AC_PosControl_Logging.cpp
9378 views
#include <AP_Logger/AP_Logger_config.h>12#if HAL_LOGGING_ENABLED34#include "AC_PosControl.h"56#include <AP_Logger/AP_Logger.h>7#include "LogStructure.h"89// Internal log writer for PSCx (North, East, Down tracking).10// Reduces duplication between Write_PSCN, PSCE, and PSCD.11// Used for logging desired/target/actual position, velocity, and acceleration per axis.12void AC_PosControl::Write_PSCx(LogMessages id, float pos_desired_m, float pos_target_m, float pos_m, float vel_desired_ms, float vel_target_ms, float vel_ms, float accel_desired_mss, float accel_target_mss, float accel_mss)13{14const struct log_PSCx pkt{15LOG_PACKET_HEADER_INIT(id),16time_us : AP_HAL::micros64(),17pos_desired : pos_desired_m,18pos_target : pos_target_m,19pos : pos_m,20vel_desired : vel_desired_ms,21vel_target : vel_target_ms,22vel : vel_ms,23accel_desired : accel_desired_mss,24accel_target : accel_target_mss,25accel : accel_mss26};27AP::logger().WriteBlock(&pkt, sizeof(pkt));28}2930// Logs position controller state along the North axis to PSCN..31// Logs desired, target, and actual position [m], velocity [m/s], and acceleration [m/s²].32void AC_PosControl::Write_PSCN(float pos_desired_m, float pos_target_m, float pos_m, float vel_desired_ms, float vel_target_ms, float vel_ms, float accel_desired_mss, float accel_target_mss, float accel_mss)33{34Write_PSCx(LOG_PSCN_MSG, pos_desired_m, pos_target_m, pos_m, vel_desired_ms, vel_target_ms, vel_ms, accel_desired_mss, accel_target_mss, accel_mss);35}3637// Logs position controller state along the East axis to PSCE.38// Logs desired, target, and actual values for position [m], velocity [m/s], and acceleration [m/s²].39void AC_PosControl::Write_PSCE(float pos_desired_m, float pos_target_m, float pos_m, float vel_desired_ms, float vel_target_ms, float vel_ms, float accel_desired_mss, float accel_target_mss, float accel_mss)40{41Write_PSCx(LOG_PSCE_MSG, pos_desired_m, pos_target_m, pos_m, vel_desired_ms, vel_target_ms, vel_ms, accel_desired_mss, accel_target_mss, accel_mss);42}4344// Logs position controller state along the Down (vertical) axis to PSCD.45// Logs desired, target, and actual values for position [m], velocity [m/s], and acceleration [m/s²].46void AC_PosControl::Write_PSCD(float pos_desired_m, float pos_target_m, float pos_m, float vel_desired_ms, float vel_target_ms, float vel_ms, float accel_desired_mss, float accel_target_mss, float accel_mss)47{48Write_PSCx(LOG_PSCD_MSG, pos_desired_m, pos_target_m, pos_m, vel_desired_ms, vel_target_ms, vel_ms, accel_desired_mss, accel_target_mss, accel_mss);49}5051// Internal log writer for PSOx (North, East, Down tracking).52// Reduces duplication between Write_PSON, PSOE, and PSOD.53// Used for logging desired/target/actual position, velocity, and acceleration per axis.54void AC_PosControl::Write_PSOx(LogMessages id, float pos_target_offset_m, float pos_offset_m,55float vel_target_offset_ms, float vel_offset_ms,56float accel_target_offset_mss, float accel_offset_mss)57{58const struct log_PSOx pkt{59LOG_PACKET_HEADER_INIT(id),60time_us : AP_HAL::micros64(),61pos_target_offset : pos_target_offset_m,62pos_offset : pos_offset_m,63vel_target_offset : vel_target_offset_ms,64vel_offset : vel_offset_ms,65accel_target_offset : accel_target_offset_mss,66accel_offset : accel_offset_mss,67};68AP::logger().WriteBlock(&pkt, sizeof(pkt));69}7071// Logs offset tracking along the North axis to PSON.72// Logs target and actual offset for position [m], velocity [m/s], and acceleration [m/s²].73void AC_PosControl::Write_PSON(float pos_target_offset_m, float pos_offset_m,74float vel_target_offset_ms, float vel_offset_ms,75float accel_target_offset_mss, float accel_offset_mss)76{77Write_PSOx(LOG_PSON_MSG, pos_target_offset_m, pos_offset_m, vel_target_offset_ms, vel_offset_ms, accel_target_offset_mss, accel_offset_mss);78}7980// Logs offset tracking along the East axis to PSOE.81// Logs target and actual offset for position [m], velocity [m/s], and acceleration [m/s²].82void AC_PosControl::Write_PSOE(float pos_target_offset_m, float pos_offset_m,83float vel_target_offset_ms, float vel_offset_ms,84float accel_target_offset_mss, float accel_offset_mss)85{86Write_PSOx(LOG_PSOE_MSG, pos_target_offset_m, pos_offset_m, vel_target_offset_ms, vel_offset_ms, accel_target_offset_mss, accel_offset_mss);87}8889// Logs offset tracking along the Down axis to PSOD.90// Logs target and actual offset for position [m], velocity [m/s], and acceleration [m/s²].91void AC_PosControl::Write_PSOD(float pos_target_offset_m, float pos_offset_m,92float vel_target_offset_ms, float vel_offset_ms,93float accel_target_offset_mss, float accel_offset_mss)94{95Write_PSOx(LOG_PSOD_MSG, pos_target_offset_m, pos_offset_m, vel_target_offset_ms, vel_offset_ms, accel_target_offset_mss, accel_offset_mss);96}9798// Logs terrain-following offset tracking along the Down axis to PSOT.99// Logs target and actual offset for position [m], velocity [m/s], and acceleration [m/s²].100void AC_PosControl::Write_PSOT(float pos_target_offset_m, float pos_offset_m,101float vel_target_offset_ms, float vel_offset_ms,102float accel_target_offset_mss, float accel_offset_mss)103{104Write_PSOx(LOG_PSOT_MSG, pos_target_offset_m, pos_offset_m, vel_target_offset_ms, vel_offset_ms, accel_target_offset_mss, accel_offset_mss);105}106107#endif // HAL_LOGGING_ENABLED108109110