2.0.12, minor fixes.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2463 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-06-03 05:36:39 +00:00
parent b640e7b68c
commit 84ef135856
6 changed files with 32 additions and 23 deletions

View File

@ -576,8 +576,11 @@ void medium_loop()
medium_loopCounter++;
// hack to stop navigation in Simple mode
if (control_mode == SIMPLE)
if (control_mode == SIMPLE){
// clear GPS data
g_gps->new_data = false;
break;
}
// Auto control modes:
if(g_gps->new_data){
@ -1240,15 +1243,15 @@ void update_alt()
//sonar_alt = sonar.read();
// decide if we're using sonar
//if ((baro_alt < 1200) || sonar_alt < 300){
if (baro_alt < 700){
if ((baro_alt < 1200) || sonar_alt < 300){
//if (baro_alt < 700){
// correct alt for angle of the sonar
float temp = cos_pitch_x * cos_roll_x;
temp = max(temp, 0.707);
sonar_alt = (float)sonar_alt * temp;
if(sonar_alt < 400){
if(sonar_alt < 450){
altitude_sensor = SONAR;
baro_alt_offset = sonar_alt - baro_alt;
}

View File

@ -8,16 +8,17 @@
byte mavdelay = 0;
// what does this do?
static uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
{
//Serial.print("target = "); Serial.print(sysid, DEC); Serial.print("\tcomp = "); Serial.println(compid, DEC);
if (sysid != mavlink_system.sysid){
return 1;
}else if(compid != mavlink_system.compid){
gcs.send_text_P(SEVERITY_LOW,PSTR("component id mismatch"));
return 0; // XXX currently not receiving correct compid from gcs
// Currently we are not checking for correct compid since APM is not passing mavlink info to any subsystem
// If it is addressed to our system ID we assume it is for us
//}else if(compid != mavlink_system.compid){
// gcs.send_text_P(SEVERITY_LOW,PSTR("component id mismatch"));
// return 1; // XXX currently not receiving correct compid from gcs
}else{
return 0; // no error
@ -70,7 +71,7 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
}
uint8_t status = MAV_STATE_ACTIVE;
uint16_t battery_remaining = 10.0 * (float)(g.pack_capacity - current_total)/g.pack_capacity; //Mavlink scaling 100% = 1000
uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000
uint8_t motor_block = false;
mavlink_msg_sys_status_send(
@ -80,7 +81,7 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
status,
load * 1000,
battery_voltage * 1000,
motor_block,
battery_remaining,
packet_drops);
break;
}

View File

@ -508,10 +508,10 @@
#endif
// if we are using fast, Disable Medium
#if LOG_ATTITUDE_FAST == ENABLED
#undef LOG_ATTITUDE_MED
#define LOG_ATTITUDE_MED DISABLED
#endif
//#if LOG_ATTITUDE_FAST == ENABLED
// #undef LOG_ATTITUDE_MED
// #define LOG_ATTITUDE_MED DISABLED
//#endif
#ifndef DEBUG_PORT
# define DEBUG_PORT 0

View File

@ -267,12 +267,6 @@
#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO
#define CURRENT_AMPS(x) ((x*(INPUT_VOLTAGE/1024.0))-CURR_AMPS_OFFSET)*CURR_AMP_PER_VOLT
#define AIRSPEED_CH 7 // The external ADC channel for the airspeed sensor
#define BATTERY_PIN1 0 // These are the pins for the voltage dividers
#define BATTERY_PIN2 1
#define BATTERY_PIN3 2
#define BATTERY_PIN4 3
/* ************************************************************** */
/* Expansion PIN's that people can use for various things. */
@ -307,6 +301,14 @@
#define RELAY_PIN 47
#define AIRSPEED_CH 7 // The external ADC channel for the airspeed sensor
#define BATTERY_PIN1 0 // These are the pins for the voltage dividers
#define BATTERY_PIN2 1
#define BATTERY_PIN3 2
#define BATTERY_PIN4 3
#define PIEZO_PIN AN5 //Last pin on the back ADC connector
// sonar
#define SonarToCm(x) (x*1.26) // Sonar raw value to centimeters

View File

@ -375,11 +375,14 @@ setup_compass(uint8_t argc, const Menu::arg *argv)
static int8_t
setup_batt_monitor(uint8_t argc, const Menu::arg *argv)
{
if(argv[1].i >= 0 && argv[1].i <= 4){
if (!strcmp_P(argv[1].str, PSTR("off"))) {
g.battery_monitoring.set_and_save(0);
} else if(argv[1].i > 0 && argv[1].i <= 4){
g.battery_monitoring.set_and_save(argv[1].i);
} else {
Serial.printf_P(PSTR("\nOptions: 0-4"));
Serial.printf_P(PSTR("\nOptions: off, 1-4"));
}
report_batt_monitor();

View File

@ -37,7 +37,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
};
// Create the top-level menu object.
MENU(main_menu, "AC 2.0.21 Beta", main_menu_commands);
MENU(main_menu, "AC 2.0.22 Beta", main_menu_commands);
void init_ardupilot()
{