forked from Archive/PX4-Autopilot
Merge pull request #1093 from DonLakeFlyer/WarningsBugs
Fix bugs found through compiler warnings
This commit is contained in:
commit
6f75d1a20f
|
@ -131,8 +131,8 @@ public:
|
|||
int set_motor_count(unsigned count);
|
||||
int set_motor_test(bool motortest);
|
||||
int set_overrideSecurityChecks(bool overrideSecurityChecks);
|
||||
int set_px4mode(int px4mode);
|
||||
int set_frametype(int frametype);
|
||||
void set_px4mode(int px4mode);
|
||||
void set_frametype(int frametype);
|
||||
unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C);
|
||||
|
||||
private:
|
||||
|
@ -330,13 +330,13 @@ MK::set_update_rate(unsigned rate)
|
|||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
void
|
||||
MK::set_px4mode(int px4mode)
|
||||
{
|
||||
_px4mode = px4mode;
|
||||
}
|
||||
|
||||
int
|
||||
void
|
||||
MK::set_frametype(int frametype)
|
||||
{
|
||||
_frametype = frametype;
|
||||
|
|
|
@ -741,7 +741,7 @@ PX4FMU::task_main()
|
|||
}
|
||||
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||
if (_control_subs > 0) {
|
||||
if (_control_subs[i] > 0) {
|
||||
::close(_control_subs[i]);
|
||||
_control_subs[i] = -1;
|
||||
}
|
||||
|
|
|
@ -182,7 +182,10 @@ float RoboClaw::getMotorPosition(e_motor motor)
|
|||
return _motor1Position;
|
||||
} else if (motor == MOTOR_2) {
|
||||
return _motor2Position;
|
||||
}
|
||||
} else {
|
||||
warnx("Unknown motor value passed to RoboClaw::getMotorPosition");
|
||||
return NAN;
|
||||
}
|
||||
}
|
||||
|
||||
float RoboClaw::getMotorSpeed(e_motor motor)
|
||||
|
@ -191,7 +194,10 @@ float RoboClaw::getMotorSpeed(e_motor motor)
|
|||
return _motor1Speed;
|
||||
} else if (motor == MOTOR_2) {
|
||||
return _motor2Speed;
|
||||
}
|
||||
} else {
|
||||
warnx("Unknown motor value passed to RoboClaw::getMotorPosition");
|
||||
return NAN;
|
||||
}
|
||||
}
|
||||
|
||||
int RoboClaw::setMotorSpeed(e_motor motor, float value)
|
||||
|
|
|
@ -603,6 +603,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
|||
// XXX TODO
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
int commander_thread_main(int argc, char *argv[])
|
||||
|
|
|
@ -1986,7 +1986,7 @@ void AttPosEKF::calcposNED(float (&posNED)[3], double lat, double lon, float hgt
|
|||
posNED[2] = -(hgt - hgtRef);
|
||||
}
|
||||
|
||||
void AttPosEKF::calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef)
|
||||
void AttPosEKF::calcLLH(float posNED[3], float &lat, float &lon, float &hgt, float latRef, float lonRef, float hgtRef)
|
||||
{
|
||||
lat = latRef + posNED[0] * earthRadiusInv;
|
||||
lon = lonRef + posNED[1] * earthRadiusInv / cos(latRef);
|
||||
|
|
|
@ -301,7 +301,7 @@ static void calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, flo
|
|||
|
||||
static void calcposNED(float (&posNED)[3], double lat, double lon, float hgt, double latRef, double lonRef, float hgtRef);
|
||||
|
||||
static void calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
|
||||
static void calcLLH(float posNED[3], float &lat, float &lon, float &hgt, float latRef, float lonRef, float hgtRef);
|
||||
|
||||
static void quat2Tnb(Mat3f &Tnb, const float (&quat)[4]);
|
||||
|
||||
|
|
|
@ -181,16 +181,13 @@ int gpio_led_main(int argc, char *argv[])
|
|||
} else {
|
||||
gpio_led_started = true;
|
||||
warnx("start, using pin: %s", pin_name);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
exit(0);
|
||||
|
||||
|
||||
} else if (!strcmp(argv[1], "stop")) {
|
||||
if (gpio_led_started) {
|
||||
gpio_led_started = false;
|
||||
warnx("stop");
|
||||
|
||||
exit(0);
|
||||
} else {
|
||||
errx(1, "not running");
|
||||
}
|
||||
|
|
|
@ -193,8 +193,12 @@ ramtron_attach(void)
|
|||
errx(1, "failed to initialize mtd driver");
|
||||
|
||||
int ret = mtd_dev->ioctl(mtd_dev, MTDIOC_SETSPEED, (unsigned long)10*1000*1000);
|
||||
if (ret != OK)
|
||||
warnx(1, "failed to set bus speed");
|
||||
if (ret != OK) {
|
||||
// FIXME: From the previous warnx call, it looked like this should have been an errx instead. Tried
|
||||
// that but setting the bug speed does fail all the time. Which was then exiting and the board would
|
||||
// not run correctly. So changed to warnx.
|
||||
warnx("failed to set bus speed");
|
||||
}
|
||||
|
||||
attached = true;
|
||||
}
|
||||
|
|
|
@ -372,6 +372,7 @@ int test_mixer(int argc, char *argv[])
|
|||
}
|
||||
|
||||
warnx("SUCCESS: No errors in mixer test");
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int
|
||||
|
|
Loading…
Reference in New Issue