Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/master'
Browse files Browse the repository at this point in the history
  • Loading branch information
rjehangir committed Apr 21, 2016
2 parents add0963 + 0e775f5 commit 9259091
Show file tree
Hide file tree
Showing 92 changed files with 1,914 additions and 712 deletions.
23 changes: 16 additions & 7 deletions APMrover2/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,10 @@
#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, &rover.v, {group_info : class::var_info} }

const AP_Param::Info Rover::var_info[] = {
// @Param: FORMAT_VERSION
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
GSCALAR(format_version, "FORMAT_VERSION", 1),

// @Param: SYSID_SW_TYPE
Expand All @@ -21,13 +25,18 @@ const AP_Param::Info Rover::var_info[] = {
// @ReadOnly: True
GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),

// misc
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: Two byte bitmap of log types to enable in dataflash
// @Values: 0:Disabled,3950:Default,4078:Default+IMU
// @Description: Bitmap of what log types to enable in dataflash. This values is made up of the sum of each of the log types you want to be saved on dataflash. On a PX4 or Pixhawk the large storage size of a microSD card means it is usually best just to enable all log types by setting this to 65535. On APM2 the smaller 4 MByte dataflash means you need to be more selective in your logging or you may run out of log space while flying (in which case it will wrap and overwrite the start of the log). The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Sonar=16384, Arming=32768, LogWhenDisarmed=65536, FullLogsArmedOnly=65535, FullLogsWhenDisarmed=131071
// @Values: 0:Disabled,5190:APM2-Default,65535:PX4/Pixhawk-Default
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,16:WHEN_DISARMED,19:IMU_RAW
// @User: Advanced
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),

// @Param: SYS_NUM_RESETS
// @DisplayName: Num Resets
// @Description: Number of APM board resets
// @User: Advanced
GSCALAR(num_resets, "SYS_NUM_RESETS", 0),

// @Param: RST_SWITCH_CH
Expand All @@ -52,7 +61,7 @@ const AP_Param::Info Rover::var_info[] = {

// @Param: SYSID_MYGCS
// @DisplayName: MAVLink ground station ID
// @Description: ID used in MAVLink protocol to identify the controlling ground station
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
Expand Down Expand Up @@ -84,8 +93,8 @@ const AP_Param::Info Rover::var_info[] = {
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),

// @Param: MAG_ENABLED
// @DisplayName: Magnetometer (compass) enabled
// @Description: This should be set to 1 if a compass is installed
// @DisplayName: Enable Compass
// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
// @User: Standard
// @Values: 0:Disabled,1:Enabled
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
Expand Down Expand Up @@ -296,7 +305,7 @@ const AP_Param::Info Rover::var_info[] = {

// @Param: FS_THR_VALUE
// @DisplayName: Throttle Failsafe Value
// @Description: The PWM level on channel 3 below which throttle failsafe triggers.
// @Description: The PWM level on the throttle channel below which throttle failsafe triggers.
// @Range: 925 1100
// @Increment: 1
// @User: Standard
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -915,6 +915,7 @@ class Copter : public AP_HAL::HAL::Callbacks {
uint32_t perf_info_get_max_time();
uint32_t perf_info_get_min_time();
uint16_t perf_info_get_num_long_running();
uint32_t perf_info_get_num_dropped();
Vector3f pv_location_to_vector(const Location& loc);
Vector3f pv_location_to_vector_with_default(const Location& loc, const Vector3f& default_posvec);
float pv_alt_above_origin(float alt_above_home_cm);
Expand Down
37 changes: 11 additions & 26 deletions ArduCopter/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -339,6 +339,7 @@ struct PACKED log_Performance {
int16_t pm_test;
uint8_t i2c_lockup_count;
uint16_t ins_error_count;
uint32_t log_dropped;
};

// Write a performance monitoring packet
Expand All @@ -352,9 +353,10 @@ void Copter::Log_Write_Performance()
max_time : perf_info_get_max_time(),
pm_test : pmTest1,
i2c_lockup_count : hal.i2c->lockup_count(),
ins_error_count : ins.error_count()
ins_error_count : ins.error_count(),
log_dropped : DataFlash.num_dropped() - perf_info_get_num_dropped(),
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}

// Write an attitude packet
Expand Down Expand Up @@ -401,21 +403,6 @@ void Copter::Log_Write_MotBatt()
#endif
}

struct PACKED log_Startup {
LOG_PACKET_HEADER;
uint64_t time_us;
};

// Write Startup packet
void Copter::Log_Write_Startup()
{
struct log_Startup pkt = {
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG),
time_us : AP_HAL::micros64()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}

struct PACKED log_Event {
LOG_PACKET_HEADER;
uint64_t time_us;
Expand Down Expand Up @@ -453,7 +440,7 @@ void Copter::Log_Write_Data(uint8_t id, int16_t value)
id : id,
data_value : value
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}

Expand All @@ -475,7 +462,7 @@ void Copter::Log_Write_Data(uint8_t id, uint16_t value)
id : id,
data_value : value
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}

Expand All @@ -496,7 +483,7 @@ void Copter::Log_Write_Data(uint8_t id, int32_t value)
id : id,
data_value : value
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}

Expand All @@ -517,7 +504,7 @@ void Copter::Log_Write_Data(uint8_t id, uint32_t value)
id : id,
data_value : value
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}

Expand All @@ -539,7 +526,7 @@ void Copter::Log_Write_Data(uint8_t id, float value)
id : id,
data_value : value
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}
}

Expand All @@ -559,7 +546,7 @@ void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
sub_system : sub_system,
error_code : error_code,
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}

void Copter::Log_Write_Baro(void)
Expand Down Expand Up @@ -731,11 +718,9 @@ const struct LogStructure Copter::log_structure[] = {
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qfffffecchh", "TimeUS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" },
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "QHHIhBH", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr" },
"PM", "QHHIhBHI", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop" },
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit" },
{ LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "Q", "TimeUS" },
{ LOG_EVENT_MSG, sizeof(log_Event),
"EV", "QB", "TimeUS,Id" },
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -260,7 +260,6 @@ enum ThrowModeState {
#define LOG_CONTROL_TUNING_MSG 0x04
#define LOG_NAV_TUNING_MSG 0x05
#define LOG_PERFORMANCE_MSG 0x06
#define LOG_STARTUP_MSG 0x0A
#define LOG_OPTFLOW_MSG 0x0C
#define LOG_EVENT_MSG 0x0D
#define LOG_PID_MSG 0x0E // deprecated
Expand Down
10 changes: 7 additions & 3 deletions ArduCopter/motors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,9 +222,13 @@ void Copter::init_disarm_motors()
#endif

// save compass offsets learned by the EKF
Vector3f magOffsets;
if (ahrs.use_compass() && ahrs.getMagOffsets(magOffsets)) {
compass.set_and_save_offsets(compass.get_primary(), magOffsets);
if (ahrs.use_compass()) {
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
Vector3f magOffsets;
if (ahrs.getMagOffsets(i, magOffsets)) {
compass.set_and_save_offsets(i, magOffsets);
}
}
}

#if AUTOTUNE_ENABLED == ENABLED
Expand Down
8 changes: 8 additions & 0 deletions ArduCopter/perf_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ static uint16_t perf_info_loop_count;
static uint32_t perf_info_max_time;
static uint32_t perf_info_min_time;
static uint16_t perf_info_long_running;
static uint32_t perf_info_log_dropped;
static bool perf_ignore_loop = false;

// perf_info_reset - reset all records of loop time to zero
Expand All @@ -24,6 +25,7 @@ void Copter::perf_info_reset()
perf_info_max_time = 0;
perf_info_min_time = 0;
perf_info_long_running = 0;
perf_info_log_dropped = DataFlash.num_dropped();
}

// perf_ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
Expand Down Expand Up @@ -77,3 +79,9 @@ uint16_t Copter::perf_info_get_num_long_running()
{
return perf_info_long_running;
}

// perf_info_get_num_dropped - get number of dropped log messages
uint32_t Copter::perf_info_get_num_dropped()
{
return perf_info_log_dropped;
}
Loading

0 comments on commit 9259091

Please sign in to comment.