Copter: move get_frame_string to Motors class

This commit is contained in:
Mark Whitehorn 2020-11-05 13:00:12 -07:00 committed by Peter Barker
parent 6b2184a53a
commit cb687a6fff
5 changed files with 34 additions and 3 deletions

View File

@ -863,6 +863,7 @@ private:
bool ekf_alt_ok() const;
void update_auto_armed();
bool should_log(uint32_t mask);
MAV_TYPE get_frame_mav_type();
const char* get_frame_string() const;
void allocate_motors(void);
bool is_tradheli() const;

View File

@ -9,7 +9,7 @@ uint8_t GCS_Copter::sysid_this_mav() const
const char* GCS_Copter::frame_string() const
{
return copter.get_frame_string();
return copter.motors->get_frame_string();
}
bool GCS_Copter::simple_input_active() const

View File

@ -548,7 +548,7 @@ bool GCS_MAVLINK_Copter::params_ready() const
void GCS_MAVLINK_Copter::send_banner()
{
GCS_MAVLINK::send_banner();
send_text(MAV_SEVERITY_INFO, "Frame: %s", copter.get_frame_string());
send_text(MAV_SEVERITY_INFO, "Frame: %s", copter.motors->get_frame_string());
}
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes

View File

@ -617,7 +617,7 @@ const struct LogStructure Copter::log_structure[] = {
void Copter::Log_Write_Vehicle_Startup_Messages()
{
// only 200(?) bytes are guaranteed by AP_Logger
logger.Write_MessageF("Frame: %s", get_frame_string());
logger.Write_MessageF("Frame: %s, Type: %s", motors->get_frame_string(), motors->get_type_string());
logger.Write_Mode((uint8_t)control_mode, control_mode_reason);
ahrs.Log_Write_Home_And_Origin();
gps.Write_AP_Logger_Log_Startup_messages();

View File

@ -484,6 +484,36 @@ const char* Copter::get_frame_string() const
default:
return "UNKNOWN";
}
// return MAV_TYPE corresponding to frame class
MAV_TYPE Copter::get_frame_mav_type()
{
switch ((AP_Motors::motor_frame_class)g2.frame_class.get()) {
case AP_Motors::MOTOR_FRAME_QUAD:
case AP_Motors::MOTOR_FRAME_UNDEFINED:
return MAV_TYPE_QUADROTOR;
case AP_Motors::MOTOR_FRAME_HEXA:
case AP_Motors::MOTOR_FRAME_Y6:
return MAV_TYPE_HEXAROTOR;
case AP_Motors::MOTOR_FRAME_OCTA:
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
return MAV_TYPE_OCTOROTOR;
case AP_Motors::MOTOR_FRAME_HELI:
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
return MAV_TYPE_HELICOPTER;
case AP_Motors::MOTOR_FRAME_TRI:
return MAV_TYPE_TRICOPTER;
case AP_Motors::MOTOR_FRAME_SINGLE:
case AP_Motors::MOTOR_FRAME_COAX:
case AP_Motors::MOTOR_FRAME_TAILSITTER:
return MAV_TYPE_COAXIAL;
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
return MAV_TYPE_DODECAROTOR;
case AP_Motors::MOTOR_FRAME_DECA:
return MAV_TYPE_DECAROTOR;
}
// unknown frame so return generic
return MAV_TYPE_GENERIC;
}
/*