mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: removed deprecated mag offset routine.
Also removed commented-out block of code from navigation.pde.
This commit is contained in:
parent
9e3c2dd105
commit
401fb4101c
|
@ -50,13 +50,6 @@ static void calc_XY_velocity(){
|
||||||
last_longitude = g_gps->longitude;
|
last_longitude = g_gps->longitude;
|
||||||
last_latitude = g_gps->latitude;
|
last_latitude = g_gps->latitude;
|
||||||
|
|
||||||
/*if(g_gps->ground_speed > 150){
|
|
||||||
* float temp = radians((float)g_gps->ground_course/100.0);
|
|
||||||
* x_actual_speed = (float)g_gps->ground_speed * sin(temp);
|
|
||||||
* y_actual_speed = (float)g_gps->ground_speed * cos(temp);
|
|
||||||
* }*/
|
|
||||||
|
|
||||||
|
|
||||||
#if INERTIAL_NAV == ENABLED
|
#if INERTIAL_NAV == ENABLED
|
||||||
// inertial_nav
|
// inertial_nav
|
||||||
xy_error_correction();
|
xy_error_correction();
|
||||||
|
|
|
@ -772,70 +772,6 @@ static void clear_offsets()
|
||||||
compass.save_offsets();
|
compass.save_offsets();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*static int8_t
|
|
||||||
* setup_mag_offset(uint8_t argc, const Menu::arg *argv)
|
|
||||||
* {
|
|
||||||
* Vector3f _offsets;
|
|
||||||
*
|
|
||||||
* if (!strcmp_P(argv[1].str, PSTR("c"))) {
|
|
||||||
* clear_offsets();
|
|
||||||
* report_compass();
|
|
||||||
* return (0);
|
|
||||||
* }
|
|
||||||
*
|
|
||||||
* print_hit_enter();
|
|
||||||
* init_compass();
|
|
||||||
*
|
|
||||||
* int16_t _min[3] = {0,0,0};
|
|
||||||
* int16_t _max[3] = {0,0,0};
|
|
||||||
*
|
|
||||||
* compass.read();
|
|
||||||
*
|
|
||||||
* while(1){
|
|
||||||
* delay(50);
|
|
||||||
* float heading;
|
|
||||||
*
|
|
||||||
* compass.read();
|
|
||||||
* heading = compass.calculate_heading(0,0); // roll = 0, pitch = 0
|
|
||||||
*
|
|
||||||
* if(compass.mag_x < _min[0]) _min[0] = compass.mag_x;
|
|
||||||
* if(compass.mag_y < _min[1]) _min[1] = compass.mag_y;
|
|
||||||
* if(compass.mag_z < _min[2]) _min[2] = compass.mag_z;
|
|
||||||
*
|
|
||||||
* // capture max
|
|
||||||
* if(compass.mag_x > _max[0]) _max[0] = compass.mag_x;
|
|
||||||
* if(compass.mag_y > _max[1]) _max[1] = compass.mag_y;
|
|
||||||
* if(compass.mag_z > _max[2]) _max[2] = compass.mag_z;
|
|
||||||
*
|
|
||||||
* // calculate offsets
|
|
||||||
* _offsets.x = (float)(_max[0] + _min[0]) / -2;
|
|
||||||
* _offsets.y = (float)(_max[1] + _min[1]) / -2;
|
|
||||||
* _offsets.z = (float)(_max[2] + _min[2]) / -2;
|
|
||||||
*
|
|
||||||
* // display all to user
|
|
||||||
* Serial.printf_P(PSTR("Heading: %u, \t (%d, %d, %d), (%4.4f, %4.4f, %4.4f)\n"),
|
|
||||||
*
|
|
||||||
* (uint16_t)(wrap_360(ToDeg(heading) * 100)) /100,
|
|
||||||
*
|
|
||||||
* compass.mag_x,
|
|
||||||
* compass.mag_y,
|
|
||||||
* compass.mag_z,
|
|
||||||
*
|
|
||||||
* _offsets.x,
|
|
||||||
* _offsets.y,
|
|
||||||
* _offsets.z);
|
|
||||||
*
|
|
||||||
* if(Serial.available() > 1){
|
|
||||||
* compass.set_offsets(_offsets);
|
|
||||||
* //compass.set_offsets(mag_offset_x, mag_offset_y, mag_offset_z);
|
|
||||||
* report_compass();
|
|
||||||
* return 0;
|
|
||||||
* }
|
|
||||||
* }
|
|
||||||
* return 0;
|
|
||||||
* }
|
|
||||||
*/
|
|
||||||
|
|
||||||
static int8_t
|
static int8_t
|
||||||
setup_optflow(uint8_t argc, const Menu::arg *argv)
|
setup_optflow(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue