@ -48,21 +48,4 @@
#define RANGE_FINDER0_DEVICE_PATH "/dev/range_finder0"
#define MB12XX_MAX_RANGEFINDERS 12 // Maximum number of Maxbotix sensors on bus
/*
* ioctl() definitions
*
* Rangefinder drivers also implement the generic sensor driver
* interfaces from drv_sensor.h
*/
#define _RANGEFINDERIOCBASE (0x7900)
#define __RANGEFINDERIOC(_n) (_IOC(_RANGEFINDERIOCBASE, _n))
/** set the minimum effective distance of the device */
#define RANGEFINDERIOCSETMINIUMDISTANCE __RANGEFINDERIOC(1)
/** set the maximum effective distance of the device */
#define RANGEFINDERIOCSETMAXIUMDISTANCE __RANGEFINDERIOC(2)
#endif /* _DRV_RANGEFINDER_H */
@ -452,18 +452,6 @@ HC_SR04::ioctl(struct file *filp, int cmd, unsigned long arg)
/* XXX implement this */
return -EINVAL;
case RANGEFINDERIOCSETMINIUMDISTANCE: {
set_minimum_distance(*(float *)arg);
return 0;
}
break;
case RANGEFINDERIOCSETMAXIUMDISTANCE: {
set_maximum_distance(*(float *)arg);
default:
/* give it to the superclass */
return CDev::ioctl(filp, cmd, arg);
@ -152,18 +152,6 @@ int LidarLite::ioctl(struct file *filp, int cmd, unsigned long arg)
reset_sensor();
return OK;
@ -444,18 +444,6 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
return I2C::ioctl(filp, cmd, arg);
@ -479,18 +479,6 @@ SF0X::ioctl(struct file *filp, int cmd, unsigned long arg)
@ -442,18 +442,6 @@ SF1XX::ioctl(struct file *filp, int cmd, unsigned long arg)
@ -445,18 +445,6 @@ SRF02::ioctl(struct file *filp, int cmd, unsigned long arg)
@ -446,18 +446,6 @@ SRF02_I2C::ioctl(struct file *filp, int cmd, unsigned long arg)
@ -509,18 +509,6 @@ TERARANGER::ioctl(struct file *filp, int cmd, unsigned long arg)