aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
Diffstat (limited to 'src')
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp8
-rw-r--r--src/drivers/px4fmu/fmu.cpp2
-rw-r--r--src/drivers/roboclaw/RoboClaw.cpp10
-rw-r--r--src/modules/commander/commander.cpp1
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.cpp2
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.h2
-rw-r--r--src/modules/gpio_led/gpio_led.c7
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp84
-rw-r--r--src/modules/mavlink/mavlink_ftp.h4
-rw-r--r--src/systemcmds/mtd/mtd.c8
-rw-r--r--src/systemcmds/tests/test_mixer.cpp1
11 files changed, 69 insertions, 60 deletions
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index 5954c40da..1c81910f6 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -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;
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 8a4bfa18c..84ea9a3bc 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -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;
}
diff --git a/src/drivers/roboclaw/RoboClaw.cpp b/src/drivers/roboclaw/RoboClaw.cpp
index dd5e4d3e0..fdaa7f27b 100644
--- a/src/drivers/roboclaw/RoboClaw.cpp
+++ b/src/drivers/roboclaw/RoboClaw.cpp
@@ -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)
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 03f5e83e2..bb42889ea 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -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[])
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
index e4b0c2b14..9622f7e40 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
@@ -1891,7 +1891,7 @@ void AttPosEKF::calcposNED(float (&posNED)[3], double lat, double lon, float hgt
posNED[2] = -(hgt - hgtReference);
}
-void AttPosEKF::calcLLH(float (&posNED)[3], double &lat, double &lon, float &hgt, double latRef, double lonRef, float hgtRef)
+void AttPosEKF::calcLLH(float posNED[3], double &lat, double &lon, float &hgt, double latRef, double lonRef, float hgtRef)
{
lat = latRef + (double)posNED[0] * earthRadiusInv;
lon = lonRef + (double)posNED[1] * earthRadiusInv / cos(latRef);
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.h b/src/modules/ekf_att_pos_estimator/estimator_23states.h
index dc461cfa1..7aad849f9 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.h
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.h
@@ -246,7 +246,7 @@ static void calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, flo
void calcposNED(float (&posNED)[3], double lat, double lon, float hgt, double latRef, double lonRef, float hgtRef);
-static void calcLLH(float (&posNED)[3], double &lat, double &lon, float &hgt, double latRef, double lonRef, float hgtRef);
+static void calcLLH(float posNED[3], double &lat, double &lon, float &hgt, double latRef, double lonRef, float hgtRef);
static void quat2Tnb(Mat3f &Tnb, const float (&quat)[4]);
diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c
index 839a7890b..7758faed7 100644
--- a/src/modules/gpio_led/gpio_led.c
+++ b/src/modules/gpio_led/gpio_led.c
@@ -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");
}
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index f1436efb8..ca846a465 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -127,7 +127,7 @@ MavlinkFTP::_worker(Request *req)
break;
case kCmdTerminate:
- errorCode = _workTerminate(req);
+ errorCode = _workTerminate(req);
break;
case kCmdReset:
@@ -222,12 +222,12 @@ MavlinkFTP::_workList(Request *req)
// no more entries?
if (result == nullptr) {
- if (hdr->offset != 0 && offset == 0) {
- // User is requesting subsequent dir entries but there were none. This means the user asked
- // to seek past EOF.
- errorCode = kErrEOF;
- }
- // Otherwise we are just at the last directory entry, so we leave the errorCode at kErrorNone to signal that
+ if (hdr->offset != 0 && offset == 0) {
+ // User is requesting subsequent dir entries but there were none. This means the user asked
+ // to seek past EOF.
+ errorCode = kErrEOF;
+ }
+ // Otherwise we are just at the last directory entry, so we leave the errorCode at kErrorNone to signal that
break;
}
@@ -266,18 +266,18 @@ MavlinkFTP::_workOpen(Request *req, bool create)
{
auto hdr = req->header();
- int session_index = _findUnusedSession();
+ int session_index = _findUnusedSession();
if (session_index < 0) {
return kErrNoSession;
}
int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
- int fd = ::open(req->dataAsCString(), oflag);
+ int fd = ::open(req->dataAsCString(), oflag);
if (fd < 0) {
return create ? kErrPerm : kErrNotFile;
}
- _session_fds[session_index] = fd;
+ _session_fds[session_index] = fd;
hdr->session = session_index;
hdr->size = 0;
@@ -290,28 +290,28 @@ MavlinkFTP::_workRead(Request *req)
{
auto hdr = req->header();
- int session_index = hdr->session;
-
- if (!_validSession(session_index)) {
+ int session_index = hdr->session;
+
+ if (!_validSession(session_index)) {
return kErrNoSession;
- }
-
- // Seek to the specified position
- printf("Seek %d\n", hdr->offset);
+ }
+
+ // Seek to the specified position
+ printf("Seek %d\n", hdr->offset);
if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) {
- // Unable to see to the specified location
+ // Unable to see to the specified location
return kErrEOF;
}
-
+
int bytes_read = ::read(_session_fds[session_index], &hdr->data[0], kMaxDataLength);
if (bytes_read < 0) {
- // Negative return indicates error other than eof
+ // Negative return indicates error other than eof
return kErrIO;
}
-
- printf("Read success %d\n", bytes_read);
+
+ printf("Read success %d\n", bytes_read);
hdr->size = bytes_read;
-
+
return kErrNone;
}
@@ -357,26 +357,26 @@ MavlinkFTP::_workTerminate(Request *req)
{
auto hdr = req->header();
- if (!_validSession(hdr->session)) {
+ if (!_validSession(hdr->session)) {
return kErrNoSession;
- }
+ }
- ::close(_session_fds[hdr->session]);
+ ::close(_session_fds[hdr->session]);
- return kErrNone;
+ return kErrNone;
}
MavlinkFTP::ErrorCode
MavlinkFTP::_workReset(void)
{
- for (size_t i=0; i<kMaxSession; i++) {
- if (_session_fds[i] != -1) {
- ::close(_session_fds[i]);
- _session_fds[i] = -1;
- }
- }
-
- return kErrNone;
+ for (size_t i=0; i<kMaxSession; i++) {
+ if (_session_fds[i] != -1) {
+ ::close(_session_fds[i]);
+ _session_fds[i] = -1;
+ }
+ }
+
+ return kErrNone;
}
bool
@@ -391,13 +391,13 @@ MavlinkFTP::_validSession(unsigned index)
int
MavlinkFTP::_findUnusedSession(void)
{
- for (size_t i=0; i<kMaxSession; i++) {
- if (_session_fds[i] == -1) {
- return i;
- }
- }
-
- return -1;
+ for (size_t i=0; i<kMaxSession; i++) {
+ if (_session_fds[i] == -1) {
+ return i;
+ }
+ }
+
+ return -1;
}
char *
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index 8a1b3fbaa..e22e61553 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -199,8 +199,8 @@ private:
ErrorCode _workRead(Request *req);
ErrorCode _workWrite(Request *req);
ErrorCode _workRemove(Request *req);
- ErrorCode _workTerminate(Request *req);
- ErrorCode _workReset();
+ ErrorCode _workTerminate(Request *req);
+ ErrorCode _workReset();
// work freelist
Request _workBufs[kRequestQueueSize];
diff --git a/src/systemcmds/mtd/mtd.c b/src/systemcmds/mtd/mtd.c
index a57eaafe7..fcc9b8366 100644
--- a/src/systemcmds/mtd/mtd.c
+++ b/src/systemcmds/mtd/mtd.c
@@ -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;
}
diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp
index df382e2c6..0b826b826 100644
--- a/src/systemcmds/tests/test_mixer.cpp
+++ b/src/systemcmds/tests/test_mixer.cpp
@@ -372,6 +372,7 @@ int test_mixer(int argc, char *argv[])
}
warnx("SUCCESS: No errors in mixer test");
+ return 0;
}
static int