using only px4_getopt() and never the unsafe getopt()

using only <px4_getopt.h> as include, cleanup related includes
added check that all the option are valid (myoptind >= argc). if there are invalid options on some script that might now lead not to run commands
This commit is contained in:
bazooka joe 2019-02-16 11:18:02 +02:00 committed by Beat Küng
parent 3db901b238
commit 922c19aa9c
20 changed files with 131 additions and 50 deletions

View File

@ -73,7 +73,7 @@
#include <uORB/uORB.h>
#include <float.h>
#include <getopt.h>
#include <px4_getopt.h>
#include "lps25h.h"
@ -967,9 +967,12 @@ int
lps25h_main(int argc, char *argv[])
{
enum LPS25H_BUS busid = LPS25H_BUS_ALL;
int ch;
while ((ch = getopt(argc, argv, "XIS:")) != EOF) {
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "XIS:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
#if (PX4_I2C_BUS_ONBOARD || PX4_SPIDEV_HMC)
@ -992,7 +995,12 @@ lps25h_main(int argc, char *argv[])
}
}
const char *verb = argv[optind];
if (myoptind >= argc) {
lps25h::usage();
exit(0);
}
const char *verb = argv[myoptind];
/*
* Start/load the driver.

View File

@ -54,7 +54,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <getopt.h>
#include <px4_getopt.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
@ -70,7 +70,6 @@
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <platforms/px4_getopt.h>
#include "mpl3115a2.h"
@ -897,8 +896,8 @@ int
mpl3115a2_main(int argc, char *argv[])
{
enum MPL3115A2_BUS busid = MPL3115A2_BUS_ALL;
int ch;
int myoptind = 1;
int ch;
const char *myoptarg = NULL;
/* jump over start/off/etc and look at options first */
@ -918,6 +917,11 @@ mpl3115a2_main(int argc, char *argv[])
}
}
if (myoptind >= argc) {
mpl3115a2::usage();
exit(0);
}
const char *verb = argv[myoptind];
/*

View File

@ -42,6 +42,7 @@
*/
#include "batt_smbus.h"
#include <px4_getopt.h>
#include <stdlib.h>
@ -100,9 +101,12 @@ BATT_SMBUS::~BATT_SMBUS()
int BATT_SMBUS::task_spawn(int argc, char *argv[])
{
enum BATT_SMBUS_BUS busid = BATT_SMBUS_BUS_ALL;
int ch;
while ((ch = getopt(argc, argv, "XTRIA:")) != EOF) {
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "XTRIA:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'X':
busid = BATT_SMBUS_BUS_I2C_EXTERNAL;
@ -130,6 +134,11 @@ int BATT_SMBUS::task_spawn(int argc, char *argv[])
}
}
if (myoptind >= argc) {
print_usage();
return PX4_ERROR;
}
for (unsigned i = 0; i < NUM_BUS_OPTIONS; i++) {
if (!is_running() && (busid == BATT_SMBUS_BUS_ALL || bus_options[i].busid == busid)) {

View File

@ -49,7 +49,7 @@
#include <cstdlib>
#include <string.h>
#include <stdio.h>
#include <platforms/px4_getopt.h>
#include <px4_getopt.h>
#ifndef CONFIG_SCHED_WORKQUEUE
# error This requires CONFIG_SCHED_WORKQUEUE.

View File

@ -58,7 +58,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <getopt.h>
#include <px4_getopt.h>
#include <perf/perf_counter.h>
#include <systemlib/err.h>
@ -1780,10 +1780,13 @@ int
adis16448_main(int argc, char *argv[])
{
enum Rotation rotation = ROTATION_NONE;
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
/* start options */
while ((ch = getopt(argc, argv, "R:")) != EOF) {
while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'R':
rotation = (enum Rotation)atoi(optarg);
@ -1795,7 +1798,13 @@ adis16448_main(int argc, char *argv[])
}
}
const char *verb = argv[optind];
if (myoptind >= argc) {
adis16448::usage();
return -1;
}
const char *verb = argv[myoptind];
/*
* Start/load the driver.

View File

@ -33,6 +33,8 @@
#include "ADIS16477.hpp"
#include <px4_getopt.h>
#define ADIS16477_DEVICE_PATH_ACCEL "/dev/adis16477_accel"
#define ADIS16477_DEVICE_PATH_GYRO "/dev/adis16477_gyro"
@ -215,10 +217,13 @@ int
adis16477_main(int argc, char *argv[])
{
enum Rotation rotation = ROTATION_NONE;
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
/* start options */
while ((ch = getopt(argc, argv, "R:")) != EOF) {
while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'R':
rotation = (enum Rotation)atoi(optarg);
@ -226,11 +231,16 @@ adis16477_main(int argc, char *argv[])
default:
adis16477::usage();
exit(0);
return 0;
}
}
const char *verb = argv[optind];
if (myoptind >= argc) {
adis16477::usage();
return -1;
}
const char *verb = argv[myoptind];
/*
* Start/load the driver.

View File

@ -35,7 +35,7 @@
#include "BMI055_gyro.hpp"
#include <px4_config.h>
#include <platforms/px4_getopt.h>
#include <px4_getopt.h>
/** driver 'main' command */
extern "C" { __EXPORT int bmi055_main(int argc, char *argv[]); }

View File

@ -16,7 +16,6 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <getopt.h>
#include <perf/perf_counter.h>
#include <systemlib/err.h>

View File

@ -72,7 +72,7 @@
#include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include <platforms/px4_getopt.h>
#include <px4_getopt.h>
#include <systemlib/err.h>
/* SPI protocol address bits */

View File

@ -76,7 +76,7 @@
#include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include <platforms/px4_getopt.h>
#include <px4_getopt.h>
#include <systemlib/err.h>
/* SPI protocol address bits */

View File

@ -54,7 +54,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <getopt.h>
#include <px4_getopt.h>
#include <perf/perf_counter.h>
#include <systemlib/err.h>
@ -1932,12 +1932,15 @@ int
lsm303d_main(int argc, char *argv[])
{
bool external_bus = false;
int ch;
enum Rotation rotation = ROTATION_NONE;
int accel_range = 8;
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
/* jump over start/off/etc and look at options first */
while ((ch = getopt(argc, argv, "XR:a:")) != EOF) {
while ((ch = px4_getopt(argc, argv, "XR:a:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'X':
external_bus = true;
@ -1957,7 +1960,12 @@ lsm303d_main(int argc, char *argv[])
}
}
const char *verb = argv[optind];
if (myoptind >= argc) {
lsm303d::usage();
exit(0);
}
const char *verb = argv[myoptind];
/*
* Start/load the driver.

View File

@ -54,6 +54,7 @@
#include <stdio.h>
#include <ctype.h>
#include <sys/stat.h>
#include <px4_getopt.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
@ -1611,10 +1612,13 @@ oreoled_main(int argc, char *argv[])
int i2cdevice = -1;
int i2c_addr = OREOLED_BASE_I2C_ADDR; /* 7bit */
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
/* jump over start/off/etc and look at options first */
while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'a':
i2c_addr = (int)strtol(optarg, NULL, 0);
@ -1630,12 +1634,12 @@ oreoled_main(int argc, char *argv[])
}
}
if (optind >= argc) {
if (myoptind >= argc) {
oreoled_usage();
exit(1);
}
const char *verb = argv[optind];
const char *verb = argv[myoptind];
int ret;
@ -2008,18 +2012,18 @@ oreoled_main(int argc, char *argv[])
}
/* check led num */
sendb.led_num = (uint8_t)strtol(argv[optind + 1], NULL, 0);
sendb.led_num = (uint8_t)strtol(argv[myoptind + 1], NULL, 0);
if (sendb.led_num > 3) {
errx(1, "led number must be between 0 ~ 3");
}
/* get bytes */
sendb.num_bytes = argc - (optind + 2);
sendb.num_bytes = argc - (myoptind + 2);
uint8_t byte_count;
for (byte_count = 0; byte_count < sendb.num_bytes; byte_count++) {
sendb.buff[byte_count] = (uint8_t)strtol(argv[byte_count + optind + 2], NULL, 0);
sendb.buff[byte_count] = (uint8_t)strtol(argv[byte_count + myoptind + 2], NULL, 0);
}
/* send bytes */

View File

@ -54,6 +54,7 @@
#include <unistd.h>
#include <stdio.h>
#include <ctype.h>
#include <px4_getopt.h>
#include <nuttx/wqueue.h>
@ -371,10 +372,13 @@ pca8574_main(int argc, char *argv[])
int i2cdevice = -1;
int pca8574adr = ADDR; // 7bit
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
// jump over start/off/etc and look at options first
while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'a':
pca8574adr = strtol(optarg, NULL, 0);
@ -390,12 +394,12 @@ pca8574_main(int argc, char *argv[])
}
}
if (optind >= argc) {
if (myoptind >= argc) {
pca8574_usage();
exit(1);
exit(0);
}
const char *verb = argv[optind];
const char *verb = argv[myoptind];
int fd;
int ret;

View File

@ -52,6 +52,7 @@
#include <unistd.h>
#include <stdio.h>
#include <ctype.h>
#include <px4_getopt.h>
#include <nuttx/wqueue.h>
#include <drivers/drv_hrt.h>
@ -293,10 +294,13 @@ rgbled_usage()
int
rgbled_pwm_main(int argc, char *argv[])
{
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
/* jump over start/off/etc and look at options first */
while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'a':
break;
@ -310,12 +314,13 @@ rgbled_pwm_main(int argc, char *argv[])
}
}
if (optind >= argc) {
if (myoptind >= argc) {
rgbled_usage();
exit(1);
exit(0);
}
const char *verb = argv[optind];
const char *verb = argv[myoptind];
if (!strcmp(verb, "start")) {
if (g_rgbled != nullptr) {

View File

@ -73,7 +73,7 @@
#include <uORB/uORB.h>
#include <float.h>
#include <getopt.h>
#include <px4_getopt.h>
#include <lib/conversion/rotation.h>
#include "hmc5883.h"
@ -1701,7 +1701,11 @@ usage()
int
hmc5883_main(int argc, char *argv[])
{
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
enum HMC5883_BUS busid = HMC5883_BUS_ALL;
enum Rotation rotation = ROTATION_NONE;
bool calibrate = false;
@ -1712,7 +1716,7 @@ hmc5883_main(int argc, char *argv[])
exit(0);
}
while ((ch = getopt(argc, argv, "XISR:CT")) != EOF) {
while ((ch = px4_getopt(argc, argv, "XISR:CT", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'R':
rotation = (enum Rotation)atoi(optarg);
@ -1746,7 +1750,13 @@ hmc5883_main(int argc, char *argv[])
}
}
const char *verb = argv[optind];
if (myoptind >= argc) {
hmc5883::usage();
exit(0);
}
const char *verb = argv[myoptind];
/*
* Start/load the driver.

View File

@ -75,7 +75,6 @@
#include <uORB/uORB.h>
#include <float.h>
#include <getopt.h>
#include <lib/conversion/rotation.h>
/*

View File

@ -35,6 +35,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#define LSM303AGR_DEVICE_PATH_MAG "/dev/lsm303agr_mag"
@ -135,11 +136,14 @@ usage()
int
lsm303agr_main(int argc, char *argv[])
{
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
enum Rotation rotation = ROTATION_NONE;
/* jump over start/off/etc and look at options first */
while ((ch = getopt(argc, argv, "XR:a:")) != EOF) {
while ((ch = px4_getopt(argc, argv, "XR:a:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'R':
rotation = (enum Rotation)atoi(optarg);
@ -151,7 +155,12 @@ lsm303agr_main(int argc, char *argv[])
}
}
const char *verb = argv[optind];
if (myoptind >= argc) {
lsm303agr::usage();
exit(0);
}
const char *verb = argv[myoptind];
/*
* Start/load the driver.

View File

@ -61,6 +61,7 @@
#include <stdio.h>
#include <ctype.h>
#include <math.h>
#include <px4_getopt.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
@ -531,10 +532,13 @@ pca9685_main(int argc, char *argv[])
int i2cdevice = -1;
int i2caddr = ADDR; // 7bit
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
// jump over start/off/etc and look at options first
while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'a':
i2caddr = strtol(optarg, NULL, 0);
@ -550,12 +554,12 @@ pca9685_main(int argc, char *argv[])
}
}
if (optind >= argc) {
if (myoptind >= argc) {
pca9685_usage();
exit(1);
exit(0);
}
const char *verb = argv[optind];
const char *verb = argv[myoptind];
int fd;
int ret;

View File

@ -52,7 +52,6 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <getopt.h>
#include <perf/perf_counter.h>
#include <systemlib/err.h>

View File

@ -46,6 +46,7 @@
#include <px4_module.h>
#include <px4_posix.h>
#include <px4_tasks.h>
#include <px4_getopt.h>
#include <stdio.h>
#include <stdbool.h>
#include <stdlib.h>
@ -56,7 +57,6 @@
#include <string.h>
#include <semaphore.h>
#include <unistd.h>
#include <platforms/px4_getopt.h>
#include <drivers/drv_hrt.h>
#include "dataman.h"