Skip to content

Commit

Permalink
removed define fpr mpu6050 -> we will initialize it every time, doesn…
Browse files Browse the repository at this point in the history
…t hurt

added new message to mavlink decoding as mfd ap uses different gps message than APM
  • Loading branch information
SamuelBrucksch committed May 19, 2015
1 parent 1a7cc30 commit 49dde44
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 54 deletions.
6 changes: 1 addition & 5 deletions open360tracker/compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@ float smoothed[3];
int magZero[3];
static uint8_t magInit = 0;

#ifdef MPU6050
void initMpu6050(){
Wire.beginTransmission(MPU6050_Address); //PWR_MGMT_1 -- DEVICE_RESET 1
Wire.write(0x6B);
Expand Down Expand Up @@ -52,7 +51,6 @@ void initMpu6050(){
Wire.write(0x02);
Wire.endTransmission();
}
#endif

void write(int address, int data)
{
Expand Down Expand Up @@ -108,9 +106,7 @@ static uint8_t bias_collect(uint8_t bias) {
}

void initCompass() {
#ifdef MPU6050
initMpu6050();
#endif
initMpu6050();

bool bret = true;
write(HMC58X3_R_CONFB, 2 << 5);
Expand Down
26 changes: 5 additions & 21 deletions open360tracker/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,6 @@
*/
//#define DEBUG

/* MPU6050 config
*
* If multiwii board uses an MPU6050 and compass is connected to its bypass port we need to enable this to configure the compass over the MPU6050
*
*/
#define MPU6050

/** PID Values
*
*/
Expand All @@ -35,15 +28,6 @@
*/
#define MAVLINK

/* MAVLINK hacks
*
* if no gps fix type or satellites are transmitted, but only coordinates then uncomment
*
*/
#define MAVLINK_NO_FIX
#define MAVLINK_NO_SATS


/* #### Baud Rate ####
*
* baud rate of telemetry input
Expand All @@ -52,7 +36,7 @@
* 115200 for RVOSD (RVGS)
* ??? for HoTT
*/
#define BAUD 115200
#define BAUD 9600

/* #### Tilt servo 0° adjustment ####
*
Expand Down Expand Up @@ -152,7 +136,7 @@
* Requires modified LiquidCrystal library: https://bitbucket.org/fmalpartida/new-liquidcrystal/downloads
*
*/
//#define LCD_DISPLAY I2C
#define LCD_DISPLAY I2C

/* ### Battery monitoring ###
*
Expand All @@ -163,9 +147,9 @@
*/
//#define BATTERYMONITORING
#ifdef BATTERYMONITORING
#define BATTERYMONITORING_RESISTOR_1 18000
#define BATTERYMONITORING_RESISTOR_2 1000
#define BATTERYMONITORING_CORRECTION 1.0 // default 1.0
//#define BATTERYMONITORING_RESISTOR_1 18000
//#define BATTERYMONITORING_RESISTOR_2 1000
//#define BATTERYMONITORING_CORRECTION 1.0 // default 1.0
#endif

/* #### Do not edit below this line */
Expand Down
52 changes: 24 additions & 28 deletions open360tracker/mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,53 +15,49 @@ static int32_t p_alt = 0; // altitude
static int16_t p_sats = 0; // number of satelites

int32_t getTargetLat() {
return p_lat;
return p_lat;
}

int32_t getTargetLon() {
return p_lon;
return p_lon;
}

int16_t getTargetAlt() {
return p_alt;
return p_alt;
}

int16_t getSats() {
return p_sats;
return p_sats;
}

void mavlink_handleMessage(mavlink_message_t* msg) {
switch (msg->msgid) {
case MAVLINK_MSG_ID_GPS_RAW_INT: {
case MAVLINK_MSG_ID_GPS_RAW_INT:
p_lat = mavlink_msg_gps_raw_int_get_lat(msg) / 100;
p_lon = mavlink_msg_gps_raw_int_get_lon(msg) / 100;
p_sats = mavlink_msg_gps_raw_int_get_satellites_visible(msg);
p_alt = mavlink_msg_gps_raw_int_get_alt(msg) / 1000;
HAS_ALT = true;

#ifdef MAVLINK_NO_FIX
#ifdef MAVLINK_NO_SATS
//we blindly trust the data that is coming in -> needed for MFD mavlink implementation
if (p_lat != 0 || p_lon != 0){
HAS_FIX = true;
}else{
HAS_FIX = false;
}
#else
if (p_sats > 0){
HAS_FIX = true;
}
#endif
#else
// fix_type: GPS lock 0-1=no fix, 2=2D, 3=3D
if (mavlink_msg_gps_raw_int_get_fix_type(msg) > 1) {
HAS_FIX = true;
}else{
HAS_FIX = false;
}
#endif

// fix_type: GPS lock 0-1=no fix, 2=2D, 3=3D
if (mavlink_msg_gps_raw_int_get_fix_type(msg) > 1) {
HAS_FIX = true;
} else {
HAS_FIX = false;
}
break;
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
p_lat = mavlink_msg_global_position_int_get_lat(msg) / 100;
p_lon = mavlink_msg_global_position_int_get_lon(msg) / 100;
p_alt = mavlink_msg_global_position_int_get_alt(msg) / 1000;
HAS_ALT = true;

if (p_lat != 0 || p_lon != 0) {
HAS_FIX = true;
} else {
HAS_FIX = false;
}
break;
}
}
}

Expand Down

0 comments on commit 49dde44

Please sign in to comment.