mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
RangeFinder: remove raw_value, orientation variables
This saves 10bytes of RAM
This commit is contained in:
parent
d19b566d97
commit
8d54e50897
@ -25,21 +25,13 @@
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
|
||||
void RangeFinder::set_orientation(int x, int y, int z)
|
||||
// Read Sensor data - post of the ahrd work is done by the child class's convert_raw_to_distance
|
||||
int16_t RangeFinder::read()
|
||||
{
|
||||
orientation_x = x;
|
||||
orientation_y = y;
|
||||
orientation_z = z;
|
||||
}
|
||||
int16_t temp_dist;
|
||||
|
||||
// Read Sensor data - only the raw_value is filled in by this parent class
|
||||
int RangeFinder::read()
|
||||
{
|
||||
int temp_dist;
|
||||
|
||||
raw_value = _analog_source->read_average();
|
||||
// convert analog value to distance in cm (using child implementation most likely)
|
||||
temp_dist = convert_raw_to_distance(raw_value);
|
||||
temp_dist = convert_raw_to_distance(_analog_source->read_average());
|
||||
|
||||
// ensure distance is within min and max
|
||||
temp_dist = constrain_float(temp_dist, min_distance, max_distance);
|
||||
|
@ -26,33 +26,28 @@ protected:
|
||||
_mode_filter(filter) {
|
||||
}
|
||||
public:
|
||||
// raw_value: read the sensor
|
||||
int raw_value;
|
||||
// distance: in cm
|
||||
int distance;
|
||||
int16_t distance;
|
||||
// maximum measurable distance: in cm
|
||||
int max_distance;
|
||||
int16_t max_distance;
|
||||
// minimum measurable distance: in cm
|
||||
int min_distance;
|
||||
|
||||
int orientation_x, orientation_y, orientation_z;
|
||||
void set_orientation(int x, int y, int z);
|
||||
int16_t min_distance;
|
||||
|
||||
/**
|
||||
* convert_raw_to_distance:
|
||||
* function that each child class should override to convert voltage
|
||||
* to distance (in cm)
|
||||
*/
|
||||
virtual int convert_raw_to_distance(int _raw_value) {
|
||||
return _raw_value;
|
||||
virtual int16_t convert_raw_to_distance(int16_t raw_value) {
|
||||
return raw_value;
|
||||
}
|
||||
/**
|
||||
* read:
|
||||
* read value from sensor and return distance in cm
|
||||
*/
|
||||
virtual int read();
|
||||
virtual int16_t read();
|
||||
|
||||
AP_HAL::AnalogSource* _analog_source;
|
||||
AP_HAL::AnalogSource* _analog_source;
|
||||
FilterInt16 * _mode_filter;
|
||||
};
|
||||
#endif // __RANGEFINDER_H__
|
||||
|
Loading…
Reference in New Issue
Block a user