mirror of https://github.com/ArduPilot/ardupilot
Added compass fix from APM
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2222 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
a19b5a5c10
commit
cce3dd73bb
|
@ -559,7 +559,8 @@ void medium_loop()
|
|||
|
||||
if(g.compass_enabled){
|
||||
compass.read(); // Read magnetometer
|
||||
compass.calculate(dcm.roll, dcm.pitch); // Calculate heading
|
||||
compass.calculate(dcm.get_dcm_matrix()); // Calculate heading
|
||||
//compass.calculate(dcm.roll, dcm.pitch); // Calculate heading
|
||||
compass.null_offsets(dcm.get_dcm_matrix());
|
||||
}
|
||||
|
||||
|
|
|
@ -97,8 +97,8 @@ void handle_process_now()
|
|||
do_repeat_relay();
|
||||
break;
|
||||
|
||||
//case MAV_CMD_DO_SET_ROI:
|
||||
// do_target_yaw();
|
||||
case MAV_CMD_DO_SET_ROI:
|
||||
do_target_yaw();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -301,25 +301,3 @@
|
|||
#define WP_SIZE 15
|
||||
#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
|
||||
#ifndef MAV_ROI_NONE
|
||||
# define MAV_ROI_NONE 0
|
||||
#endif
|
||||
#ifndef MAV_ROI_WPNEXT
|
||||
# define MAV_ROI_WPNEXT 1
|
||||
#endif
|
||||
#ifndef MAV_ROI_WPINDEX
|
||||
# define MAV_ROI_WPINDEX 2
|
||||
#endif
|
||||
#ifndef MAV_ROI_LOCATION
|
||||
# define MAV_ROI_LOCATION 3
|
||||
#endif
|
||||
#ifndef MAV_ROI_TARGET
|
||||
# define MAV_ROI_TARGET 4
|
||||
#endif
|
||||
|
||||
*/
|
Loading…
Reference in New Issue