-
Notifications
You must be signed in to change notification settings - Fork 17.7k
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
Add AP_AngleSensor Driver with AS5048B Support, Integrate with Windvane #25749
base: master
Are you sure you want to change the base?
Conversation
3b066e2
to
6b1c917
Compare
If the goal is to support on more than rover your better off adding it to AP_Vehicle straight away. |
Looks like there is some debug code that needs removing. |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
unless this stays Rover only and @rmackay9 agrees to have it default for that vehicle, this should be a build optioned, and probably default excluded in minimize_common
Thanks for the reviews - a summary of TODOs
|
f81dafa
to
92efa4a
Compare
cf78001
to
263f474
Compare
All reviews addressed and build is passing |
d3cfcec
to
5e4543d
Compare
This creates a generic angle sensor/absolute encoder library with initial support for the AS5048B Magnetic Rotary encoder. This driver follows the typical frontend/backend pattern and future support for additional encoders is expected. This is initially integrated with AP_WindVane, but could be used anywhere that absolute angle measurements are required.
This adds a backend for AP_Windvane using the new AP_AngleSensor driver. The "DIR_PIN" param is overloaded to select the absolute encoder backend.
4bb2669
to
375e769
Compare
Rebased and Refactored to "AngleSensor" per discussion on discord. |
////////////////////////////////////////////////////////////////////////////// | ||
// Angle Sensor Driver - useful for wind vanes | ||
#ifndef ANGLESENSOR_ENABLED | ||
#define ANGLESENSOR_ENABLED ENABLED |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Does this work? One problem with moving it to AP vehicle is that you can't see these vehicle level config files anymore. We typically have to get round it with dummy methods, which is annoying. AP_AIS
would be a example.
// @Group: _ | ||
// @Path: AP_AngleSensor_Params.cpp | ||
AP_SUBGROUPINFO(_params[0], "_", 0, AP_AngleSensor, AP_AngleSensor_Params), |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
// @Group: _ | |
// @Path: AP_AngleSensor_Params.cpp | |
AP_SUBGROUPINFO(_params[0], "_", 0, AP_AngleSensor, AP_AngleSensor_Params), | |
// @Group: 1_ | |
// @Path: AP_AngleSensor_Params.cpp | |
AP_SUBGROUPINFO(_params[0], "1_", 1, AP_AngleSensor, AP_AngleSensor_Params), |
My preference would be to number the first instance too, just keep things more consistent. Also param indexes should start at 1.
#if ANGLE_SENSOR_MAX_INSTANCES > 1 | ||
// @Group: 2_ | ||
// @Path: AP_AngleSensor_Params.cpp | ||
AP_SUBGROUPINFO(_params[1], "2_", 1, AP_AngleSensor, AP_AngleSensor_Params), | ||
#endif |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
#if ANGLE_SENSOR_MAX_INSTANCES > 1 | |
// @Group: 2_ | |
// @Path: AP_AngleSensor_Params.cpp | |
AP_SUBGROUPINFO(_params[1], "2_", 1, AP_AngleSensor, AP_AngleSensor_Params), | |
#endif | |
#if ANGLE_SENSOR_MAX_INSTANCES > 1 | |
// @Group: 2_ | |
// @Path: AP_AngleSensor_Params.cpp | |
AP_SUBGROUPINFO(_params[1], "2_", 2, AP_AngleSensor, AP_AngleSensor_Params), | |
#endif |
This moves to index 2 so we can avoid 0 on for the first set.
void AP_AngleSensor::update(void) | ||
{ | ||
for (uint8_t i=0; i<_num_instances; i++) { | ||
if (drivers[i] != nullptr && _params[i]._type != ANGLESENSOR_TYPE_NONE) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I presume the type check is so you can runtime disable? But that would just leave the state unchanged which could still be healthy?
Better to either not allow runtime disable, or if disabled then overwrite the state.
angle_0 : (float)get_angle_radians(0), | ||
quality_0 : (uint8_t)get_signal_quality(0), | ||
angle_1 : (float)get_angle_radians(1), | ||
quality_1 : (uint8_t)get_signal_quality(1), |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Per Instance logging is much more flexible. You would add the sensor index with the magic #
unit.
enum AngleSensor_Type : uint8_t { | ||
ANGLESENSOR_TYPE_NONE = ANGLE_SENSOR_TYPE_NONE, | ||
ANGLESENSOR_TYPE_AS5048B = 1, | ||
}; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
enum AngleSensor_Type : uint8_t { | |
ANGLESENSOR_TYPE_NONE = ANGLE_SENSOR_TYPE_NONE, | |
ANGLESENSOR_TYPE_AS5048B = 1, | |
}; | |
enum class TYPE : uint8_t { | |
NONE = ANGLE_SENSOR_TYPE_NONE, | |
AS5048B = 1, | |
}; |
Enum class's are preferred, you would then use like this: TYPE::AS5048B
. Externally (its public so I guess there is a user somewhere) it would be AP_AngleSensor::TYPE::AS5048B
so you still have the same descriptiveness of ANGLESENSOR_TYPE_AS5048B
}; | ||
|
||
// The AngleSensor_State structure is filled in by the backend driver | ||
struct AngleSensor_State { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Does this need to be public?
_state.last_reading_ms = last_reading_ms; | ||
} | ||
|
||
#endif // AP_ANGLESENSOR_ENABLED |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
#endif // AP_ANGLESENSOR_ENABLED | |
#endif // AP_ANGLESENSOR_ENABLED | |
// @Description: What type of Angle Sensor is connected | ||
// @Values: 0:None,1:AS5048B | ||
// @User: Standard | ||
AP_GROUPINFO_FLAGS("TYPE", 0, AP_AngleSensor_Params, _type, ANGLE_SENSOR_TYPE_NONE, AP_PARAM_FLAG_ENABLE), |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Per the top level, start at index 1.
// @Param: BUS | ||
// @DisplayName: Angle Sensor Serial Bus Index | ||
// @Description: Angle Sensor Serial Bus Index | ||
// @Values: 1: I2C1, 2: I2C2, 3: I2C3 | ||
// @User: Standard | ||
AP_GROUPINFO("BUS", 4, AP_AngleSensor_Params, _bus, ANGLE_SENSOR_BUS_DEFAULT), | ||
|
||
// @Param: ADDR | ||
// @DisplayName: Serial Bus Address | ||
// @Description: Serial Bus Address | ||
// @Increment: 1 | ||
// @User: Standard | ||
AP_GROUPINFO("ADDR", 5, AP_AngleSensor_Params, _addr, ANGLE_SENSOR_ADDR_DEFAULT), |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
These could be in a i2c sub table that only gets loaded for this driver. As we add more types we don't want all the params all the time. A potentiometer backend would add a pin and voltage and angle pairs.
AP_Int8 _direction; | ||
}; | ||
|
||
#endif // AP_ANGLESENSOR_ENABLED |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
#endif // AP_ANGLESENSOR_ENABLED | |
#endif // AP_ANGLESENSOR_ENABLED | |
@@ -0,0 +1,74 @@ | |||
/* | |||
* RangeFinder test code |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
?
@@ -49,8 +50,8 @@ const AP_Param::GroupInfo AP_WindVane::var_info[] = { | |||
|
|||
// @Param: DIR_PIN | |||
// @DisplayName: Wind vane analog voltage pin for direction | |||
// @Description: Analog input pin to read as wind vane direction | |||
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6,103:Pixhawk SBUS | |||
// @Description: Analog input pin to read as wind vane direction. If the Wind Vane type is Angle Sensor, this parameter selects the Angle Sensor Instance. |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think my preference would be to encode this in the type. Re-using pin is a bit odd. Maybe we would skip some and start at 20 for type.
"20:AngleSensor 1, 21:AngleSensor 2, 22:AngleSensor 3" ect.
Or I guess we flip it the other way from the start and have a function in the angle sensor lib. We usually endup doing that anyway when there are several instances. Servos and RC are examples, and we have just done relay.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think I'm going to go with the first option - that's how it's done for RPM which is the closest example I can think of. I think that the function flip makes the most sense for outputs which can only be assigned one function at a time. In theory, an angle sensor could be consumed by multiple devices at a time.
} | ||
} | ||
|
||
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED | |
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED | |
if (angle_sensor_driver != nullptr) { | ||
if (angle_sensor_driver->healthy(_encoder_instance)) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
if (angle_sensor_driver != nullptr) { | |
if (angle_sensor_driver->healthy(_encoder_instance)) { | |
if ((angle_sensor_driver != nullptr) && (angle_sensor_driver->healthy(_encoder_instance)) { |
Lazy evaluation means you can do these in one go.
uint8_t _encoder_instance = 0; | ||
}; | ||
|
||
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED | |
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED | |
Thanks for the reviews- working on cleaning this up now |
This change includes the following:
While this change only integrates the driver with AP_WindVane, I expect that this driver will have future use for:
This was tested on a MATEK H743 Board.