Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Rover/Log.cpp
Views: 1798
#include "Rover.h"12#include <AP_RangeFinder/AP_RangeFinder_Backend.h>34#if HAL_LOGGING_ENABLED56// Write an attitude packet7void Rover::Log_Write_Attitude()8{9float desired_pitch = degrees(g2.attitude_control.get_desired_pitch());10const Vector3f targets(0.0f, desired_pitch, 0.0f);1112ahrs.Write_Attitude(targets);1314AP::ahrs().Log_Write();1516// log steering rate controller17logger.Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info());18logger.Write_PID(LOG_PIDA_MSG, g2.attitude_control.get_throttle_speed_pid_info());1920// log pitch control for balance bots21if (is_balancebot()) {22logger.Write_PID(LOG_PIDP_MSG, g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info());23}2425// log heel to sail control for sailboats26if (g2.sailboat.sail_enabled()) {27logger.Write_PID(LOG_PIDR_MSG, g2.attitude_control.get_sailboat_heel_pid().get_pid_info());28}29}3031#if AP_RANGEFINDER_ENABLED32// Write a range finder depth message33void Rover::Log_Write_Depth()34{35// only log depth on boats36if (!rover.is_boat() || !rangefinder.has_orientation(ROTATION_PITCH_270)) {37return;38}3940// get position41Location loc;42IGNORE_RETURN(ahrs.get_location(loc));4344for (uint8_t i=0; i<rangefinder.num_sensors(); i++) {45const AP_RangeFinder_Backend *s = rangefinder.get_backend(i);4647if (s == nullptr || s->orientation() != ROTATION_PITCH_270 || !s->has_data()) {48continue;49}5051// check if new sensor reading has arrived52const uint32_t reading_ms = s->last_reading_ms();53if (reading_ms == rangefinder_last_reading_ms[i]) {54continue;55}56rangefinder_last_reading_ms[i] = reading_ms;5758float temp_C;59if (!s->get_temp(temp_C)) {60temp_C = 0.0f;61}6263// @LoggerMessage: DPTH64// @Description: Depth messages on boats with downwards facing range finder65// @Field: TimeUS: Time since system startup66// @Field: Inst: Instance67// @Field: Lat: Latitude68// @Field: Lng: Longitude69// @Field: Depth: Depth as detected by the sensor70// @Field: Temp: Temperature7172logger.Write("DPTH", "TimeUS,Inst,Lat,Lng,Depth,Temp",73"s#DUmO", "F-GG00", "QBLLff",74AP_HAL::micros64(),75i,76loc.lat,77loc.lng,78(double)(s->distance()),79temp_C);80}81}82#endif8384// guided mode logging85struct PACKED log_GuidedTarget {86LOG_PACKET_HEADER;87uint64_t time_us;88uint8_t type;89float pos_target_x;90float pos_target_y;91float pos_target_z;92float vel_target_x;93float vel_target_y;94float vel_target_z;95};9697// Write a Guided mode target98void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target)99{100struct log_GuidedTarget pkt = {101LOG_PACKET_HEADER_INIT(LOG_GUIDEDTARGET_MSG),102time_us : AP_HAL::micros64(),103type : target_type,104pos_target_x : pos_target.x,105pos_target_y : pos_target.y,106pos_target_z : pos_target.z,107vel_target_x : vel_target.x,108vel_target_y : vel_target.y,109vel_target_z : vel_target.z110};111logger.WriteBlock(&pkt, sizeof(pkt));112}113114struct PACKED log_Nav_Tuning {115LOG_PACKET_HEADER;116uint64_t time_us;117float wp_distance;118float wp_bearing;119float nav_bearing;120uint16_t yaw;121float xtrack_error;122};123124// Write a navigation tuning packet125void Rover::Log_Write_Nav_Tuning()126{127struct log_Nav_Tuning pkt = {128LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),129time_us : AP_HAL::micros64(),130wp_distance : control_mode->get_distance_to_destination(),131wp_bearing : control_mode->wp_bearing(),132nav_bearing : control_mode->nav_bearing(),133yaw : (uint16_t)ahrs.yaw_sensor,134xtrack_error : control_mode->crosstrack_error()135};136logger.WriteBlock(&pkt, sizeof(pkt));137}138139void Rover::Log_Write_Sail()140{141// only log sail if present142if (!g2.sailboat.sail_enabled()) {143return;144}145146float wind_dir_tack = logger.quiet_nanf();147uint8_t current_tack = 0;148if (g2.windvane.enabled()) {149wind_dir_tack = degrees(g2.windvane.get_tack_threshold_wind_dir_rad());150current_tack = uint8_t(g2.windvane.get_current_tack());151}152153// @LoggerMessage: SAIL154// @Description: Sailboat information155// @Field: TimeUS: Time since system startup156// @Field: Tack: Current tack, 0 = port, 1 = starboard157// @Field: TackThr: Apparent wind angle used for tack threshold158// @Field: MainOut: Normalized mainsail output159// @Field: WingOut: Normalized wingsail output160// @Field: MastRotOut: Normalized direct-rotation mast output161// @Field: VMG: Velocity made good (speed at which vehicle is making progress directly towards destination)162163logger.Write("SAIL", "TimeUS,Tack,TackThr,MainOut,WingOut,MastRotOut,VMG",164"s-d%%%n", "F000000", "QBfffff",165AP_HAL::micros64(),166current_tack,167(double)wind_dir_tack,168(double)g2.motors.get_mainsail(),169(double)g2.motors.get_wingsail(),170(double)g2.motors.get_mast_rotation(),171(double)g2.sailboat.get_VMG());172}173174struct PACKED log_Steering {175LOG_PACKET_HEADER;176uint64_t time_us;177int16_t steering_in;178float steering_out;179float desired_lat_accel;180float lat_accel;181float desired_turn_rate;182float turn_rate;183};184185// Write a steering packet186void Rover::Log_Write_Steering()187{188float lat_accel = logger.quiet_nanf();189g2.attitude_control.get_lat_accel(lat_accel);190struct log_Steering pkt = {191LOG_PACKET_HEADER_INIT(LOG_STEERING_MSG),192time_us : AP_HAL::micros64(),193steering_in : channel_steer->get_control_in(),194steering_out : g2.motors.get_steering(),195desired_lat_accel : control_mode->get_desired_lat_accel(),196lat_accel : lat_accel,197desired_turn_rate : degrees(g2.attitude_control.get_desired_turn_rate()),198turn_rate : degrees(ahrs.get_yaw_rate_earth())199};200logger.WriteBlock(&pkt, sizeof(pkt));201}202203struct PACKED log_Throttle {204LOG_PACKET_HEADER;205uint64_t time_us;206int16_t throttle_in;207float throttle_out;208float desired_speed;209float speed;210float accel_x;211};212213// Write a throttle control packet214void Rover::Log_Write_Throttle()215{216const Vector3f accel = ins.get_accel();217float speed = logger.quiet_nanf();218g2.attitude_control.get_forward_speed(speed);219struct log_Throttle pkt = {220LOG_PACKET_HEADER_INIT(LOG_THR_MSG),221time_us : AP_HAL::micros64(),222throttle_in : channel_throttle->get_control_in(),223throttle_out : g2.motors.get_throttle(),224desired_speed : g2.attitude_control.get_desired_speed(),225speed : speed,226accel_x : accel.x227};228logger.WriteBlock(&pkt, sizeof(pkt));229}230231void Rover::Log_Write_RC(void)232{233logger.Write_RCIN();234logger.Write_RCOUT();235#if AP_RSSI_ENABLED236if (rssi.enabled()) {237logger.Write_RSSI();238}239#endif240}241242void Rover::Log_Write_Vehicle_Startup_Messages()243{244// only 200(?) bytes are guaranteed by AP_Logger245logger.Write_Mode((uint8_t)control_mode->mode_number(), control_mode_reason);246ahrs.Log_Write_Home_And_Origin();247gps.Write_AP_Logger_Log_Startup_messages();248}249250// type and unit information can be found in251// libraries/AP_Logger/Logstructure.h; search for "log_Units" for252// units and "Format characters" for field type information253254const LogStructure Rover::log_structure[] = {255LOG_COMMON_STRUCTURES,256257// @LoggerMessage: THR258// @Description: Throttle related messages259// @Field: TimeUS: Time since system startup260// @Field: ThrIn: Throttle Input261// @Field: ThrOut: Throttle Output262// @Field: DesSpeed: Desired speed263// @Field: Speed: Actual speed264// @Field: AccX: Acceleration265266{ LOG_THR_MSG, sizeof(log_Throttle),267"THR", "Qhffff", "TimeUS,ThrIn,ThrOut,DesSpeed,Speed,AccX", "s--nno", "F--000" },268269// @LoggerMessage: NTUN270// @Description: Navigation Tuning information - e.g. vehicle destination271// @URL: http://ardupilot.org/rover/docs/navigation.html272// @Field: TimeUS: Time since system startup273// @Field: WpDist: distance to the current navigation waypoint274// @Field: WpBrg: bearing to the current navigation waypoint275// @Field: DesYaw: the vehicle's desired heading276// @Field: Yaw: the vehicle's current heading277// @Field: XTrack: the vehicle's current distance from the current travel segment278279{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),280"NTUN", "QfffHf", "TimeUS,WpDist,WpBrg,DesYaw,Yaw,XTrack", "smhhhm", "F000B0" },281282// @LoggerMessage: STER283// @Description: Steering related messages284// @Field: TimeUS: Time since system startup285// @Field: SteerIn: Steering input286// @Field: SteerOut: Normalized steering output287// @Field: DesLatAcc: Desired lateral acceleration288// @Field: LatAcc: Actual lateral acceleration289// @Field: DesTurnRate: Desired turn rate290// @Field: TurnRate: Actual turn rate291292{ LOG_STEERING_MSG, sizeof(log_Steering),293"STER", "Qhfffff", "TimeUS,SteerIn,SteerOut,DesLatAcc,LatAcc,DesTurnRate,TurnRate", "s--ookk", "F--0000" },294295// @LoggerMessage: GUIP296// @Description: Guided mode target information297// @Field: TimeUS: Time since system startup298// @Field: Type: Type of guided mode299// @Field: pX: Target position, X-Axis300// @Field: pY: Target position, Y-Axis301// @Field: pZ: Target position, Z-Axis302// @Field: vX: Target velocity, X-Axis303// @Field: vY: Target velocity, Y-Axis304// @Field: vZ: Target velocity, Z-Axis305306{ LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget),307"GUIP", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },308};309310uint8_t Rover::get_num_log_structures() const311{312return ARRAY_SIZE(log_structure);313}314315#endif // LOGGING_ENABLED316317318