APM:Copter
setup.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // report_compass - displays compass information. Also called by compassmot.pde
5 {
6  hal.console->printf("Compass\n");
8 
10 
11  // mag declination
12  hal.console->printf("Mag Dec: %4.4f\n",
13  (double)degrees(compass.get_declination()));
14 
15  // mag offsets
16  Vector3f offsets;
17  for (uint8_t i=0; i<compass.get_count(); i++) {
18  offsets = compass.get_offsets(i);
19  // mag offsets
20  hal.console->printf("Mag%d off: %4.4f, %4.4f, %4.4f\n",
21  (int)i,
22  (double)offsets.x,
23  (double)offsets.y,
24  (double)offsets.z);
25  }
26 
27  // motor compensation
28  hal.console->printf("Motor Comp: ");
30  hal.console->printf("Off\n");
31  }else{
33  hal.console->printf("Throttle");
34  }
36  hal.console->printf("Current");
37  }
38  Vector3f motor_compensation;
39  for (uint8_t i=0; i<compass.get_count(); i++) {
40  motor_compensation = compass.get_motor_compensation(i);
41  hal.console->printf("\nComMot%d: %4.2f, %4.2f, %4.2f\n",
42  (int)i,
43  (double)motor_compensation.x,
44  (double)motor_compensation.y,
45  (double)motor_compensation.z);
46  }
47  }
48  print_blanks(1);
49 }
50 
51 void Copter::print_blanks(int16_t num)
52 {
53  while(num > 0) {
54  num--;
55  hal.console->printf("\n");
56  }
57 }
58 
60 {
61  for (int i = 0; i < 40; i++) {
62  hal.console->printf("-");
63  }
64  hal.console->printf("\n");
65 }
66 
68 {
69  if(b)
70  hal.console->printf("en");
71  else
72  hal.console->printf("dis");
73  hal.console->printf("abled\n");
74 }
75 
77 {
78  hal.console->printf("FW Ver: %d\n",(int)(g.k_format_version));
79  print_divider();
80  print_blanks(2);
81 }
#define AP_COMPASS_MOT_COMP_DISABLED
float get_declination() const
AP_HAL::UARTDriver * console
struct _USB_OTG_GOTGCTL_TypeDef::@51 b
void print_enabled(bool b)
Definition: setup.cpp:67
#define AP_COMPASS_MOT_COMP_THROTTLE
void report_compass()
Definition: setup.cpp:4
static const uint16_t k_format_version
Definition: Parameters.h:17
const Vector3f & get_motor_compensation(uint8_t i) const
virtual void printf(const char *,...) FMT_PRINTF(2
void print_blanks(int16_t num)
Definition: setup.cpp:51
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
const Vector3f & get_offsets(uint8_t i) const
void report_version()
Definition: setup.cpp:76
uint8_t get_count(void) const
Parameters g
Definition: Copter.h:208
AP_Int8 compass_enabled
Definition: Parameters.h:401
void print_divider(void)
Definition: setup.cpp:59
Compass compass
Definition: Copter.h:235
uint8_t get_motor_compensation_type() const
#define degrees(x)
#define AP_COMPASS_MOT_COMP_CURRENT