changes for Max and tri-copters

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2184 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-05-07 20:26:43 +00:00
parent 6f0a639898
commit b0d7ec3747
4 changed files with 5 additions and 6 deletions

View File

@ -87,8 +87,8 @@ void read_trim_switch()
// this is a test for Max's tri-copter
if(g.frame_type == TRI_FRAME){
g.rc_4.trim(); // yaw
g.rc_4.save_eeprom();
//g.rc_4.trim(); // yaw
//g.rc_4.save_eeprom();
}
}
trim_flag = false;

View File

@ -302,7 +302,6 @@
#define ONBOARD_PARAM_NAME_LENGTH 15
#define MAX_WAYPOINTS ((EEPROM_MAX_ADDR - WP_START_BYTE) / WP_SIZE) - 1 // - 1 to be safe
/*
#ifndef MAV_CMD_DO_ROI
# define MAV_CMD_DO_ROI 201
#endif
@ -322,4 +321,4 @@
# define MAV_ROI_TARGET 4
#endif
*/
//*/

View File

@ -127,7 +127,7 @@ set_servos_4()
motor_out[CH_4] = g.rc_3.radio_out - g.rc_2.pwm_out;
// this is a compensation for the angle of the yaw motor. Its linear, but should work ok.
motor_out[CH_4] += (float)(abs(g.rc_4.control_in)) * .013;
//motor_out[CH_4] += (float)(abs(g.rc_4.control_in)) * .013;
// servo Yaw
APM_RC.OutputCh(CH_7, g.rc_4.radio_out);

View File

@ -511,7 +511,7 @@ setup_frame(uint8_t argc, const Menu::arg *argv)
g.frame_type = HEXAP_FRAME;
}else{
Serial.printf_P(PSTR("\nOptions:[+, x, tri, hexa, y6]\n"));
Serial.printf_P(PSTR("\nOptions:[+, x, tri, hexa+, hexax, y6]\n"));
report_frame();
return 0;
}