Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Delete unnecessary driver #includes continued... #12437

Merged
merged 8 commits into from
Jul 9, 2019
3 changes: 0 additions & 3 deletions src/drivers/batt_smbus/batt_smbus.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,6 @@
*/

#include "batt_smbus.h"
#include <px4_getopt.h>

#include <stdlib.h>

extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]);

Expand Down
71 changes: 36 additions & 35 deletions src/drivers/batt_smbus/batt_smbus.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,48 +43,49 @@

#pragma once

#include <drivers/drv_hrt.h>
#include <ecl/geo/geo.h>
#include <lib/drivers/smbus/SMBus.hpp>
#include <mathlib/mathlib.h>
#include <px4_config.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <perf/perf_counter.h>
#include <platforms/px4_module.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/topics/battery_status.h>

#define DATA_BUFFER_SIZE 32

#define BATT_CELL_VOLTAGE_THRESHOLD_RTL 0.5f ///< Threshold in volts to RTL if cells are imbalanced
#define BATT_CELL_VOLTAGE_THRESHOLD_FAILED 1.5f ///< Threshold in volts to Land if cells are imbalanced

#define BATT_CURRENT_UNDERVOLTAGE_THRESHOLD 5.0f ///< Threshold in amps to disable undervoltage protection
#define BATT_VOLTAGE_UNDERVOLTAGE_THRESHOLD 3.4f ///< Threshold in volts to re-enable undervoltage protection

#define BATT_SMBUS_CURRENT 0x0A ///< current register
#define BATT_SMBUS_AVERAGE_CURRENT 0x0B ///< current register
#define BATT_SMBUS_ADDR 0x0B ///< Default 7 bit address I2C address. 8 bit = 0x16
#define BATT_SMBUS_ADDR_MIN 0x00 ///< lowest possible address
#define BATT_SMBUS_ADDR_MAX 0xFF ///< highest possible address
#define BATT_SMBUS_PEC_POLYNOMIAL 0x07 ///< Polynomial for calculating PEC
#define BATT_SMBUS_TEMP 0x08 ///< temperature register
#define BATT_SMBUS_VOLTAGE 0x09 ///< voltage register
#define BATT_SMBUS_FULL_CHARGE_CAPACITY 0x10 ///< capacity when fully charged
#define BATT_SMBUS_RUN_TIME_TO_EMPTY 0x11 ///< predicted remaining battery capacity based on the present rate of discharge in min
#define BATT_SMBUS_AVERAGE_TIME_TO_EMPTY 0x12 ///< predicted remaining battery capacity based on the present rate of discharge in min
#define BATT_SMBUS_REMAINING_CAPACITY 0x0F ///< predicted remaining battery capacity as a percentage
#define BATT_SMBUS_CYCLE_COUNT 0x17 ///< number of cycles the battery has experienced
#define BATT_SMBUS_DESIGN_CAPACITY 0x18 ///< design capacity register
#define BATT_SMBUS_DESIGN_VOLTAGE 0x19 ///< design voltage register
#define BATT_SMBUS_MANUFACTURER_NAME 0x20 ///< manufacturer name
#define BATT_SMBUS_MANUFACTURE_DATE 0x1B ///< manufacture date register
#define BATT_SMBUS_SERIAL_NUMBER 0x1C ///< serial number register
#define BATT_SMBUS_MEASUREMENT_INTERVAL_US 100000 ///< time in microseconds, measure at 10Hz
#define BATT_SMBUS_TIMEOUT_US 1000000 ///< timeout looking for battery 10seconds after startup
#include "board_config.h"
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This was a mix of spaces and tabs... it is uniform now, my apologies for the diff.


#define DATA_BUFFER_SIZE 32

#define BATT_CELL_VOLTAGE_THRESHOLD_RTL 0.5f ///< Threshold in volts to RTL if cells are imbalanced
#define BATT_CELL_VOLTAGE_THRESHOLD_FAILED 1.5f ///< Threshold in volts to Land if cells are imbalanced

#define BATT_CURRENT_UNDERVOLTAGE_THRESHOLD 5.0f ///< Threshold in amps to disable undervoltage protection
#define BATT_VOLTAGE_UNDERVOLTAGE_THRESHOLD 3.4f ///< Threshold in volts to re-enable undervoltage protection

#define BATT_SMBUS_CURRENT 0x0A ///< current register
#define BATT_SMBUS_AVERAGE_CURRENT 0x0B ///< current register
#define BATT_SMBUS_ADDR 0x0B ///< Default 7 bit address I2C address. 8 bit = 0x16
#define BATT_SMBUS_ADDR_MIN 0x00 ///< lowest possible address
#define BATT_SMBUS_ADDR_MAX 0xFF ///< highest possible address
#define BATT_SMBUS_PEC_POLYNOMIAL 0x07 ///< Polynomial for calculating PEC
#define BATT_SMBUS_TEMP 0x08 ///< temperature register
#define BATT_SMBUS_VOLTAGE 0x09 ///< voltage register
#define BATT_SMBUS_FULL_CHARGE_CAPACITY 0x10 ///< capacity when fully charged
#define BATT_SMBUS_RUN_TIME_TO_EMPTY 0x11 ///< predicted remaining battery capacity based on the present rate of discharge in min
#define BATT_SMBUS_AVERAGE_TIME_TO_EMPTY 0x12 ///< predicted remaining battery capacity based on the present rate of discharge in min
#define BATT_SMBUS_REMAINING_CAPACITY 0x0F ///< predicted remaining battery capacity as a percentage
#define BATT_SMBUS_CYCLE_COUNT 0x17 ///< number of cycles the battery has experienced
#define BATT_SMBUS_DESIGN_CAPACITY 0x18 ///< design capacity register
#define BATT_SMBUS_DESIGN_VOLTAGE 0x19 ///< design voltage register
#define BATT_SMBUS_MANUFACTURER_NAME 0x20 ///< manufacturer name
#define BATT_SMBUS_MANUFACTURE_DATE 0x1B ///< manufacture date register
#define BATT_SMBUS_SERIAL_NUMBER 0x1C ///< serial number register
#define BATT_SMBUS_MEASUREMENT_INTERVAL_US 100000 ///< time in microseconds, measure at 10Hz
#define BATT_SMBUS_TIMEOUT_US 1000000 ///< timeout looking for battery 10seconds after startup
#define BATT_SMBUS_MANUFACTURER_ACCESS 0x00
#define BATT_SMBUS_MANUFACTURER_DATA 0x23
#define BATT_SMBUS_MANUFACTURER_DATA 0x23
#define BATT_SMBUS_MANUFACTURER_BLOCK_ACCESS 0x44
#define BATT_SMBUS_SECURITY_KEYS 0x0035
#define BATT_SMBUS_SECURITY_KEYS 0x0035
#define BATT_SMBUS_CELL_1_VOLTAGE 0x3F
#define BATT_SMBUS_CELL_2_VOLTAGE 0x3E
#define BATT_SMBUS_CELL_3_VOLTAGE 0x3D
Expand All @@ -94,8 +95,8 @@
#define BATT_SMBUS_ENABLED_PROTECTIONS_A_ADDRESS 0x4938
#define BATT_SMBUS_SEAL 0x0030

#define BATT_SMBUS_ENABLED_PROTECTIONS_A_DEFAULT 0xcf
#define BATT_SMBUS_ENABLED_PROTECTIONS_A_CUV_DISABLED 0xce
#define BATT_SMBUS_ENABLED_PROTECTIONS_A_DEFAULT 0xcf
#define BATT_SMBUS_ENABLED_PROTECTIONS_A_CUV_DISABLED 0xce

#define NUM_BUS_OPTIONS (sizeof(bus_options)/sizeof(bus_options[0]))

Expand Down
17 changes: 4 additions & 13 deletions src/drivers/camera_capture/camera_capture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,31 +38,22 @@

#pragma once

#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <fcntl.h>
#include <stdbool.h>
#include <poll.h>
#include <mathlib/mathlib.h>
#include <systemlib/err.h>
#include <parameters/param.h>
#include <string.h>

#include <px4_config.h>
#include <parameters/param.h>
#include <px4_defines.h>
#include <px4_module.h>
#include <px4_tasks.h>
#include <px4_workqueue.h>

#include <drivers/device/ringbuffer.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_input_capture.h>
#include <drivers/device/ringbuffer.h>

#include <uORB/uORB.h>
#include <uORB/topics/camera_trigger.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/uORB.h>

#define PX4FMU_DEVICE_PATH "/dev/px4fmu"

Expand Down
16 changes: 1 addition & 15 deletions src/drivers/differential_pressure/ets/ets_airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,22 +40,8 @@

#include <float.h>

#include <px4_config.h>

#include <drivers/device/i2c.h>

#include <systemlib/err.h>
#include <parameters/param.h>
#include <perf/perf_counter.h>
#include <px4_getopt.h>

#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/ringbuffer.h>

#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <drivers/airspeed/airspeed.h>
#include <px4_getopt.h>

/* I2C bus address */
#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
Expand Down
16 changes: 1 addition & 15 deletions src/drivers/differential_pressure/ms4525/ms4525_airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,22 +49,8 @@
* - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf)
*/

#include <px4_config.h>
#include <px4_getopt.h>

#include <drivers/device/i2c.h>

#include <systemlib/err.h>
#include <parameters/param.h>
#include <perf/perf_counter.h>

#include <mathlib/math/filter/LowPassFilter2p.hpp>

#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>

#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <px4_getopt.h>
#include <uORB/topics/system_power.h>

#include <drivers/airspeed/airspeed.h>
Expand Down
8 changes: 1 addition & 7 deletions src/drivers/differential_pressure/ms5525/MS5525.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,15 +35,9 @@
#define DRIVERS_MS5525_AIRSPEED_HPP_

#include <drivers/airspeed/airspeed.h>
#include <drivers/device/i2c.h>
#include <drivers/drv_airspeed.h>
#include <math.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <px4_config.h>
#include <sys/types.h>
#include <perf/perf_counter.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/uORB.h>
#include <px4_getopt.h>

/* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */
static constexpr uint8_t I2C_ADDRESS_1_MS5525DSO = 0x76;
Expand Down
4 changes: 0 additions & 4 deletions src/drivers/differential_pressure/ms5525/MS5525_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,6 @@

#include "MS5525.hpp"

#include <px4_getopt.h>

#include <stdlib.h>

// Driver 'main' command.
extern "C" __EXPORT int ms5525_airspeed_main(int argc, char *argv[]);

Expand Down
4 changes: 2 additions & 2 deletions src/drivers/differential_pressure/sdp3x/SDP3X.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,15 @@
*
****************************************************************************/

#include "SDP3X.hpp"

/**
* @file SDP3X.hpp
*
* Driver for Sensirion SDP3X Differential Pressure Sensor
*
*/

#include "SDP3X.hpp"

int
SDP3X::probe()
{
Expand Down
8 changes: 1 addition & 7 deletions src/drivers/differential_pressure/sdp3x/SDP3X.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,15 +43,9 @@
#define DRIVERS_SDP3X_AIRSPEED_HPP_

#include <drivers/airspeed/airspeed.h>
#include <drivers/device/i2c.h>
#include <drivers/drv_airspeed.h>
#include <math.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <px4_config.h>
#include <sys/types.h>
#include <perf/perf_counter.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/uORB.h>
#include <px4_getopt.h>

#define I2C_ADDRESS_1_SDP3X 0x21
#define I2C_ADDRESS_2_SDP3X 0x22
Expand Down
4 changes: 0 additions & 4 deletions src/drivers/differential_pressure/sdp3x/SDP3X_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,6 @@

#include "SDP3X.hpp"

#include <px4_getopt.h>

#include <stdlib.h>

// Driver 'main' command.
extern "C" __EXPORT int sdp3x_airspeed_main(int argc, char *argv[]);

Expand Down
9 changes: 3 additions & 6 deletions src/drivers/gps/definitions.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,20 +39,17 @@

#pragma once

#include <drivers/drv_hrt.h>
#include <px4_defines.h>
#include <px4_time.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/satellite_info.h>

#define GPS_INFO(...) PX4_INFO(__VA_ARGS__)
#define GPS_WARN(...) PX4_WARN(__VA_ARGS__)
#define GPS_ERR(...) PX4_ERR(__VA_ARGS__)

#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/satellite_info.h>

#define gps_usleep px4_usleep

#include <drivers/drv_hrt.h>

/**
* Get the current time in us. Function signature:
* uint64_t hrt_absolute_time()
Expand Down
39 changes: 6 additions & 33 deletions src/drivers/gps/gps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,52 +41,25 @@
#include <nuttx/arch.h>
#endif


#include <termios.h>

#ifndef __PX4_QURT
#include <poll.h>
#endif

#include <termios.h>

#include <fcntl.h>
#include <sys/ioctl.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdio.h>
#include <stdbool.h>
#include <stdlib.h>
#include <string.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>
#include <px4_cli.h>
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_module.h>
#include <px4_tasks.h>
#include <px4_time.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>
#include <systemlib/err.h>
#include <parameters/param.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/satellite_info.h>
#include <uORB/topics/gps_inject_data.h>
#include <uORB/topics/gps_dump.h>
#include <uORB/topics/gps_inject_data.h>

#include <board_config.h>

#include "devices/src/ubx.h"
#include "devices/src/mtk.h"
#include "devices/src/ashtech.h"
#include "devices/src/emlid_reach.h"
#include "devices/src/mtk.h"
#include "devices/src/ubx.h"

#ifdef __PX4_LINUX
#include <linux/spi/spidev.h>
Expand Down
7 changes: 3 additions & 4 deletions src/drivers/heater/heater.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,11 @@

#pragma once

#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_module.h>
#include <px4_module_params.h>
#include <px4_config.h>
#include <px4_getopt.h>

#include <px4_module.h>
#include <px4_module_params.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/sensor_accel.h>
Expand Down
8 changes: 4 additions & 4 deletions src/drivers/imu/adis16448/ADIS16448.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,15 +42,15 @@
* @author Lorenz Meier <[email protected]>
*/

#include <ecl/geo/geo.h>
#include <perf/perf_counter.h>
#include <drivers/device/spi.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <conversion/rotation.h>
#include <ecl/geo/geo.h>
#include <lib/conversion/rotation.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/barometer/PX4Barometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
#include <perf/perf_counter.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>

using namespace time_literals;

Expand Down
3 changes: 0 additions & 3 deletions src/drivers/imu/adis16477/ADIS16477.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,6 @@

#include "ADIS16477.hpp"

#include <px4_config.h>
#include <ecl/geo/geo.h>

#define DIR_READ 0x00
#define DIR_WRITE 0x80

Expand Down
Loading