delete unused IOCTL ACCELIOCSRANGE

This commit is contained in:
Daniel Agar 2018-11-03 14:28:11 -04:00 committed by Lorenz Meier
parent b0c3e12139
commit 5d3d120705
14 changed files with 10 additions and 83 deletions

View File

@ -134,7 +134,7 @@ then
mpl3115a2 -X start
# Internal SPI (accel + mag)
fxos8701cq start -a 8 -R 0
fxos8701cq start -R 0
# Internal SPI (gyro)
fxas21002c start -R 0

View File

@ -82,9 +82,6 @@ struct accel_calibration_s {
/** set the accel scaling constants to the structure pointed to by (arg) */
#define ACCELIOCSSCALE _ACCELIOC(5)
/** set the accel measurement range to handle at least (arg) g */
#define ACCELIOCSRANGE _ACCELIOC(7)
/** get the current accel measurement range in g */
#define ACCELIOCGRANGE _ACCELIOC(8)

View File

@ -1086,9 +1086,6 @@ ADIS16448::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
return -EINVAL;
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);

View File

@ -425,9 +425,6 @@ ADIS16477::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
return -EINVAL;
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);

View File

@ -481,9 +481,6 @@ BMA180::ioctl(struct file *filp, int cmd, unsigned long arg)
memcpy(&_accel_scale, (struct accel_calibration_s *) arg, sizeof(_accel_scale));
return OK;
case ACCELIOCSRANGE:
return set_range(arg);
case ACCELIOCGRANGE:
return _current_range;

View File

@ -432,9 +432,6 @@ BMI055_accel::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
return set_accel_range(arg);
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);

View File

@ -668,9 +668,6 @@ BMI160::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
return set_accel_range(arg);
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);

View File

@ -899,10 +899,6 @@ FXOS8701CQ::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
/* arg needs to be in G */
return accel_set_range(arg);
case ACCELIOCGRANGE:
/* convert to m/s^2 and return rounded in G */
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
@ -1677,7 +1673,7 @@ namespace fxos8701cq
FXOS8701CQ *g_dev;
void start(bool external_bus, enum Rotation rotation, unsigned range);
void start(bool external_bus, enum Rotation rotation);
void test();
void reset();
void info();
@ -1693,7 +1689,7 @@ void test_error();
* up and running or failed to detect the sensor.
*/
void
start(bool external_bus, enum Rotation rotation, unsigned range)
start(bool external_bus, enum Rotation rotation)
{
int fd;
@ -1735,10 +1731,6 @@ start(bool external_bus, enum Rotation rotation, unsigned range)
goto fail;
}
if (ioctl(fd, ACCELIOCSRANGE, range) < 0) {
goto fail;
}
#if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)
int fd_mag;
fd_mag = open(FXOS8701C_DEVICE_PATH_MAG, O_RDONLY);
@ -1987,7 +1979,6 @@ usage()
PX4_INFO("options:");
PX4_INFO(" -X (external bus)");
PX4_INFO(" -R rotation");
PX4_INFO(" -a range in ga 2,4,8");
}
} // namespace
@ -1998,7 +1989,6 @@ fxos8701cq_main(int argc, char *argv[])
bool external_bus = false;
int ch;
enum Rotation rotation = ROTATION_NONE;
int accel_range = 8;
int myoptind = 1;
const char *myoptarg = NULL;
@ -2013,10 +2003,6 @@ fxos8701cq_main(int argc, char *argv[])
rotation = (enum Rotation)atoi(myoptarg);
break;
case 'a':
accel_range = atoi(myoptarg);
break;
default:
fxos8701cq::usage();
exit(0);
@ -2030,7 +2016,7 @@ fxos8701cq_main(int argc, char *argv[])
*/
if (!strcmp(verb, "start")) {
fxos8701cq::start(external_bus, rotation, accel_range);
fxos8701cq::start(external_bus, rotation);
}
/*

View File

@ -911,10 +911,6 @@ LSM303D::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
/* arg needs to be in G */
return accel_set_range(arg);
case ACCELIOCGRANGE:
/* convert to m/s^2 and return rounded in G */
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
@ -1824,10 +1820,6 @@ start(bool external_bus, enum Rotation rotation, unsigned range)
goto fail;
}
if (ioctl(fd, ACCELIOCSRANGE, range) < 0) {
goto fail;
}
fd_mag = open(LSM303D_DEVICE_PATH_MAG, O_RDONLY);
/* don't fail if open cannot be opened */

View File

@ -1385,9 +1385,6 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
return set_accel_range(arg);
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);
@ -2134,8 +2131,8 @@ struct mpu6000_bus_option {
#define NUM_BUS_OPTIONS (sizeof(bus_options)/sizeof(bus_options[0]))
void start(enum MPU6000_BUS busid, enum Rotation rotation, int range, int device_type);
bool start_bus(struct mpu6000_bus_option &bus, enum Rotation rotation, int range, int device_type);
void start(enum MPU6000_BUS busid, enum Rotation rotation, int device_type);
bool start_bus(struct mpu6000_bus_option &bus, enum Rotation rotation, int device_type);
void stop(enum MPU6000_BUS busid);
void test(enum MPU6000_BUS busid);
static struct mpu6000_bus_option &find_bus(enum MPU6000_BUS busid);
@ -2165,7 +2162,7 @@ struct mpu6000_bus_option &find_bus(enum MPU6000_BUS busid)
* start driver for a specific bus option
*/
bool
start_bus(struct mpu6000_bus_option &bus, enum Rotation rotation, int range, int device_type)
start_bus(struct mpu6000_bus_option &bus, enum Rotation rotation, int device_type)
{
int fd = -1;
@ -2210,10 +2207,6 @@ start_bus(struct mpu6000_bus_option &bus, enum Rotation rotation, int range, int
goto fail;
}
if (ioctl(fd, ACCELIOCSRANGE, range) < 0) {
goto fail;
}
close(fd);
return true;
@ -2239,7 +2232,7 @@ fail:
* or failed to detect the sensor.
*/
void
start(enum MPU6000_BUS busid, enum Rotation rotation, int range, int device_type)
start(enum MPU6000_BUS busid, enum Rotation rotation, int device_type)
{
bool started = false;
@ -2260,7 +2253,7 @@ start(enum MPU6000_BUS busid, enum Rotation rotation, int range, int device_type
continue;
}
started |= start_bus(bus_options[i], rotation, range, device_type);
started |= start_bus(bus_options[i], rotation, device_type);
}
exit(started ? 0 : 1);
@ -2464,7 +2457,6 @@ usage()
warnx(" -z internal2 SPI bus");
warnx(" -T 6000|20608|20602 (default 6000)");
warnx(" -R rotation");
warnx(" -a accel range (in g)");
}
} // namespace
@ -2479,7 +2471,6 @@ mpu6000_main(int argc, char *argv[])
enum MPU6000_BUS busid = MPU6000_BUS_ALL;
int device_type = MPU_DEVICE_TYPE_MPU6000;
enum Rotation rotation = ROTATION_NONE;
int accel_range = MPU6000_ACCEL_DEFAULT_RANGE_G;
while ((ch = px4_getopt(argc, argv, "T:XISsZzR:a:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
@ -2515,10 +2506,6 @@ mpu6000_main(int argc, char *argv[])
rotation = (enum Rotation)atoi(myoptarg);
break;
case 'a':
accel_range = atoi(myoptarg);
break;
default:
mpu6000::usage();
return 0;
@ -2536,7 +2523,7 @@ mpu6000_main(int argc, char *argv[])
* Start/load the driver.
*/
if (!strcmp(verb, "start")) {
mpu6000::start(busid, rotation, accel_range, device_type);
mpu6000::start(busid, rotation, device_type);
}
if (!strcmp(verb, "stop")) {

View File

@ -845,9 +845,6 @@ MPU9250::ioctl(struct file *filp, int cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
return set_accel_range(arg);
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);

View File

@ -583,10 +583,6 @@ ACCELSIM::devIOCTL(unsigned long cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
/* arg needs to be in G */
return accel_set_range(ul_arg);
case ACCELIOCGRANGE:
/* convert to m/s^2 and return rounded in G */
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);

View File

@ -718,9 +718,6 @@ GYROSIM::devIOCTL(unsigned long cmd, unsigned long arg)
}
}
case ACCELIOCSRANGE:
return set_accel_range(arg);
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2) / CONSTANTS_ONE_G + 0.5f);

View File

@ -332,16 +332,6 @@ do_accel(int argc, char *argv[])
return 1;
}
} else if (argc == 3 && !strcmp(argv[0], "range")) {
/* set the range to i G */
ret = ioctl(fd, ACCELIOCSRANGE, strtoul(argv[2], NULL, 0));
if (ret) {
PX4_ERR("range could not be set");
return 1;
}
} else {
print_usage();
return 1;