mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
Copter: default FRAME_CLASS
This commit is contained in:
parent
0ac00dbfd6
commit
217757fdc8
@ -1083,6 +1083,7 @@ private:
|
||||
void update_auto_armed();
|
||||
void check_usb_mux(void);
|
||||
bool should_log(uint32_t mask);
|
||||
void set_default_frame_class();
|
||||
uint8_t get_frame_mav_type();
|
||||
const char* get_frame_string();
|
||||
bool current_mode_has_user_takeoff(bool must_navigate);
|
||||
|
@ -52,6 +52,9 @@ void Copter::init_rc_in()
|
||||
// init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration
|
||||
void Copter::init_rc_out()
|
||||
{
|
||||
// default frame class to match firmware if possible
|
||||
set_default_frame_class();
|
||||
|
||||
motors.set_update_rate(g.rc_speed);
|
||||
motors.set_loop_rate(scheduler.get_loop_rate_hz());
|
||||
motors.init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_orientation.get());
|
||||
|
@ -460,6 +460,36 @@ bool Copter::should_log(uint32_t mask)
|
||||
#endif
|
||||
}
|
||||
|
||||
// default frame_class to match firmware if possible
|
||||
void Copter::set_default_frame_class()
|
||||
{
|
||||
switch (FRAME_CONFIG) {
|
||||
case QUAD_FRAME:
|
||||
case HEXA_FRAME:
|
||||
case OCTA_FRAME:
|
||||
case OCTA_QUAD_FRAME:
|
||||
case Y6_FRAME:
|
||||
// reset frame_class to undefined if firmware does not match
|
||||
// Note: this assumes that Y6 is the highest numbered frame to be supported by the AP_Motors_Matrix class
|
||||
if (g2.frame_class > AP_Motors::MOTOR_FRAME_Y6) {
|
||||
g2.frame_class = AP_Motors::MOTOR_FRAME_UNDEFINED;
|
||||
}
|
||||
break;
|
||||
case TRI_FRAME:
|
||||
g2.frame_class = AP_Motors::MOTOR_FRAME_TRI;
|
||||
break;
|
||||
case HELI_FRAME:
|
||||
g2.frame_class = AP_Motors::MOTOR_FRAME_HELI;
|
||||
break;
|
||||
case SINGLE_FRAME:
|
||||
g2.frame_class = AP_Motors::MOTOR_FRAME_SINGLE;
|
||||
break;
|
||||
case COAX_FRAME:
|
||||
g2.frame_class = AP_Motors::MOTOR_FRAME_COAX;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// return MAV_TYPE corresponding to frame class
|
||||
uint8_t Copter::get_frame_mav_type()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user