drivers: various whitespace

This commit is contained in:
Ban Siesta 2015-05-24 10:05:42 +01:00
parent 21dfd0243d
commit 362fc205b3
5 changed files with 18 additions and 18 deletions

View File

@ -921,10 +921,10 @@ HMC5883::collect()
_temperature_counter = 0;
ret = _interface->read(ADDR_TEMP_OUT_MSB,
ret = _interface->read(ADDR_TEMP_OUT_MSB,
raw_temperature, sizeof(raw_temperature));
if (ret == OK) {
int16_t temp16 = (((int16_t)raw_temperature[0]) << 8) +
int16_t temp16 = (((int16_t)raw_temperature[0]) << 8) +
raw_temperature[1];
new_report.temperature = 25 + (temp16 / (16*8.0f));
_temperature_error_count = 0;
@ -1146,8 +1146,8 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
ret = -EIO;
goto out;
}
float cal[3] = {fabsf(expected_cal[0] / report.x),
fabsf(expected_cal[1] / report.y),
float cal[3] = {fabsf(expected_cal[0] / report.x),
fabsf(expected_cal[1] / report.y),
fabsf(expected_cal[2] / report.z)};
if (cal[0] > 0.7f && cal[0] < 1.35f &&
@ -1381,7 +1381,7 @@ HMC5883::print_info()
printf("poll interval: %u ticks\n", _measure_ticks);
printf("output (%.2f %.2f %.2f)\n", (double)_last_report.x, (double)_last_report.y, (double)_last_report.z);
printf("offsets (%.2f %.2f %.2f)\n", (double)_scale.x_offset, (double)_scale.y_offset, (double)_scale.z_offset);
printf("scaling (%.2f %.2f %.2f) 1/range_scale %.2f range_ga %.2f\n",
printf("scaling (%.2f %.2f %.2f) 1/range_scale %.2f range_ga %.2f\n",
(double)_scale.x_scale, (double)_scale.y_scale, (double)_scale.z_scale,
(double)(1.0f/_range_scale), (double)_range_ga);
printf("temperature %.2f\n", (double)_last_report.temperature);
@ -1451,7 +1451,7 @@ start_bus(struct hmc5883_bus_option &bus, enum Rotation rotation)
bus.dev = NULL;
return false;
}
int fd = open(bus.devpath, O_RDONLY);
if (fd < 0) {
return false;
@ -1505,7 +1505,7 @@ struct hmc5883_bus_option &find_bus(enum HMC5883_BUS busid)
busid == bus_options[i].busid) && bus_options[i].dev != NULL) {
return bus_options[i];
}
}
}
errx(1, "bus %u not started", (unsigned)busid);
}
@ -1750,7 +1750,7 @@ hmc5883_main(int argc, char *argv[])
}
}
const char *verb = argv[optind];
const char *verb = argv[optind];
/*
* Start/load the driver.

View File

@ -588,7 +588,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota
_debug_enabled = true;
_device_id.devid_s.devtype = DRV_ACC_DEVTYPE_LSM303D;
/* Prime _mag with parents devid. */
_mag->_device_id.devid = _device_id.devid;
_mag->_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LSM303D;
@ -1399,9 +1399,9 @@ LSM303D::start()
_mag_reports->flush();
/* start polling at the specified rate */
hrt_call_every(&_accel_call,
hrt_call_every(&_accel_call,
1000,
_call_accel_interval - LSM303D_TIMER_REDUCTION,
_call_accel_interval - LSM303D_TIMER_REDUCTION,
(hrt_callout)&LSM303D::measure_trampoline, this);
hrt_call_every(&_mag_call, 1000, _call_mag_interval, (hrt_callout)&LSM303D::mag_measure_trampoline, this);
}

View File

@ -896,7 +896,7 @@ start_bus(struct ms5611_bus_option &bus)
bus.dev = NULL;
return false;
}
int fd = open(bus.devpath, O_RDONLY);
/* set the poll rate to default, starts automatic data collection */
@ -955,7 +955,7 @@ struct ms5611_bus_option &find_bus(enum MS5611_BUS busid)
busid == bus_options[i].busid) && bus_options[i].dev != NULL) {
return bus_options[i];
}
}
}
errx(1,"bus %u not started", (unsigned)busid);
}

View File

@ -123,13 +123,13 @@ private:
ringbuffer::RingBuffer *_reports;
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
bool _collect_phase;
orb_advert_t _px4flow_topic;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
enum Rotation _sensor_rotation;
/**
@ -486,10 +486,10 @@ PX4FLOW::collect()
report.gyro_temperature = f_integral.gyro_temperature;//Temperature * 100 in centi-degrees Celsius
report.sensor_id = 0;
/* rotate measurements according to parameter */
float zeroval = 0.0f;
rotate_3f(_sensor_rotation, report.pixel_flow_x_integral, report.pixel_flow_y_integral, zeroval);
rotate_3f(_sensor_rotation, report.pixel_flow_x_integral, report.pixel_flow_y_integral, zeroval);
if (_px4flow_topic < 0) {
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &report);

View File

@ -82,7 +82,7 @@
#define TRONE_WHO_AM_I_REG 0x01 /* Who am I test register */
#define TRONE_WHO_AM_I_REG_VAL 0xA1
/* Device limits */
#define TRONE_MIN_DISTANCE (0.20f)
#define TRONE_MAX_DISTANCE (14.00f)