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

Add AP_AngleSensor Driver with AS5048B Support, Integrate with Windvane #25749

Open
wants to merge 6 commits into
base: master
Choose a base branch
from

Conversation

DavidIngraham
Copy link
Contributor

@DavidIngraham DavidIngraham commented Dec 11, 2023

This change includes the following:

  • AP_AngleSensor: a new sensor driver frontend for digital angle sensors.
  • AP_AngleSensor_AS5048B: An AP_AngleSensor backend for the AS5048B I2C Magnetic Encoder.
  • AP_WindVane_AngleSensor: An AP_WindVane backend that uses AP_AngleSensor.
  • AP_Vehicle Support for AngleSensor (Disabled by default for all vehicles except Rover)

While this change only integrates the driver with AP_WindVane, I expect that this driver will have future use for:

  • Scripting - especially for variable geometry frame configurations
  • Fault Detection for Tiltrotors
  • AOA/Sideslip sensors (see stale PR: Create simulator for AS5600 AOA sensor #16397)
  • Motor Position control for Mounts and End Effectors (AP_Periph based servo firmware?)
  • Cyclic motor control for swashplateless rotors

This was tested on a MATEK H743 Board.

@IamPete1
Copy link
Member

If the goal is to support on more than rover your better off adding it to AP_Vehicle straight away.

@IamPete1
Copy link
Member

Looks like there is some debug code that needs removing.

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Dec 11, 2023
@Hwurzburg Hwurzburg self-requested a review December 11, 2023 13:45
Copy link
Collaborator

@Hwurzburg Hwurzburg left a 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

@DavidIngraham
Copy link
Contributor Author

DavidIngraham commented Dec 11, 2023

Thanks for the reviews - a summary of TODOs

@DavidIngraham
Copy link
Contributor Author

All reviews addressed and build is passing

@DavidIngraham DavidIngraham force-pushed the AP_AbsoluteEncoder branch 2 times, most recently from d3cfcec to 5e4543d Compare December 17, 2023 16:17
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.
@DavidIngraham
Copy link
Contributor Author

Rebased and Refactored to "AngleSensor" per discussion on discord.

@DavidIngraham DavidIngraham changed the title Add AP_AbsoluteEncoder Driver with AS5048B Support, Integrate with Windvane Add AP_AngleSensor Driver with AS5048B Support, Integrate with Windvane Dec 30, 2023
//////////////////////////////////////////////////////////////////////////////
// Angle Sensor Driver - useful for wind vanes
#ifndef ANGLESENSOR_ENABLED
#define ANGLESENSOR_ENABLED ENABLED
Copy link
Member

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.

Comment on lines +28 to +30
// @Group: _
// @Path: AP_AngleSensor_Params.cpp
AP_SUBGROUPINFO(_params[0], "_", 0, AP_AngleSensor, AP_AngleSensor_Params),
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
// @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.

Comment on lines +32 to +36
#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
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
#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) {
Copy link
Member

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.

Comment on lines +95 to +98
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),
Copy link
Member

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.

Comment on lines +48 to +51
enum AngleSensor_Type : uint8_t {
ANGLESENSOR_TYPE_NONE = ANGLE_SENSOR_TYPE_NONE,
ANGLESENSOR_TYPE_AS5048B = 1,
};
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
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 {
Copy link
Member

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
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
#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),
Copy link
Member

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.

Comment on lines +18 to +30
// @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),
Copy link
Member

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
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
#endif // AP_ANGLESENSOR_ENABLED
#endif // AP_ANGLESENSOR_ENABLED

@@ -0,0 +1,74 @@
/*
* RangeFinder test code
Copy link
Member

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.
Copy link
Member

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.

Copy link
Contributor Author

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
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED

Comment on lines +34 to +35
if (angle_sensor_driver != nullptr) {
if (angle_sensor_driver->healthy(_encoder_instance)) {
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
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
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED
#endif //AP_WINDVANE_ANGLESENSOR_ENABLED

@DavidIngraham
Copy link
Contributor Author

Thanks for the reviews- working on cleaning this up now

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants