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 actuators, magnetometer, barometer and imu #2

Open
wants to merge 2 commits into
base: main
Choose a base branch
from

Conversation

PonomarevDA
Copy link
Contributor

Actuator (ESC/Servo) and minimal sensors set interfaces

Here I've added some interfaces to complete the minimal UAV application. Please read their short descriptions:

It is a compromise based on how ArduPilot and PX4 handle DroneCAN, what we have in the current UDRAL, the old DS015 and some comments from Andrew Tridgell.

Below you can see few additional notes.

1. Actuators (ESC and servo) feedback

For ESC both autopilots use esc.Status. They skip power_rating_pct, so we have:

  • current,
  • voltage,
  • temperature,
  • rpm,
  • error_counter.

For servos autopilots use actuator.Status the following fields for logging only:

  • position (meters or radians),
  • force,
  • speed,
  • power_rating_pct.

Both autopilots have additional messages:

  • PX4 additionally adds uavcan.equipment.ice.reciprocating.Status that is a custom solution for specific applications with an internal combustion engine.
  • ArduPilot adds a custom servo interface called com.volz.servo. In addition to the actuator.Status fields, this message also has: temperature and current.

I see the following reasons why we should split this data into a few logical groups instead of packing it into a single message:

  • We can disable unused data fields. If we have only limited information about the ESC/Servo, this approach would be much more efficient from a bandwidth utilization point of view. For example, the motor temperature requires an external sensor, which makes this information quite rare.
  • We can also win by reducing the publication rate for data that can't change its state rapidly. Again, the temperature is a good candidate.
  • It may be useful to publish some data at a flexible rate, such as electric current. A pilot doesn't normally need to look at this field, although it is the most interesting field during an investigation of an accidental motor stop or unexpected behavior. It is useful for the ESC to vary its publication rate depending on the situation.
  • This approach also allows for easier customization. Instead of DroneCAN's internal combustion engine status, I would prefer to use angular_velocity, temperature + some extensions as a separate message, but not current and voltage.

A single message approach doesn't require additional registers for the configuration and may be more easier to parse for an autopilot, but here we don't have the strict requirement to process everything at once as with GNSS.

Both the single and the separated messages have the same bandwidth utilization at the fixed publication rate.

2. Actuators setpoint

DroneCAN suggests the following messages:

  • RawCommand, which is a highly optimized message that supports up to 20 commands in a single message. It is used for ESC.
  • ArrayCommand, whose key feature is the ability to send individual commands. It supports up to 15 actuators and it can handle up to 256 servos in total. Each command is exactly 4 bytes long. It is used for servo.
  • ArmingStatus is used to report the vehicle status.

The UDRAL setpoint is based on the assumption that we have a constant number of actuators in an actuator group during the flight. It is expected to use Vector4 for a quadcopter, Vector8 for a octocopter and so on. For a subscriber, the size of the Vector doesn't matter due to Implicit zero extension of missing data rule. Compared to DroneCAN:

  • The UDRAL setpoint is optimized almost as well as RawCommand. It uses more CAN-frames only in few cases.
  • It has all advantages of ArrayCommand. By diving actuators into group we can control them individually.

Design issue.
It was rightly mentioned by Andrew Tridgell that The design is that if commanding 8 ESCs you use a Vector8, for 16 ESCs you use Vector16, etc, so it leads to code when we control only a specific number.

reg_udral_service_actuator_common_sp_Vector31_0_1 vector31_sp;

...

uint8_t buf[reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
size_t buf_size = reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;

if (number_of_channels <= 4) {
    reg_udral_service_actuator_common_sp_Vector4_0_1_serialize_((const reg_udral_service_actuator_common_sp_Vector4_0_1*)&vector31_sp, buf, &buf_size);
} else if (number_of_channels <= 8) {
    reg_udral_service_actuator_common_sp_Vector8_0_1_serialize_((const reg_udral_service_actuator_common_sp_Vector8_0_1*)&vector31_sp, buf, &buf_size);
} else {
    reg_udral_service_actuator_common_sp_Vector31_0_1_serialize_(&vector31_sp, buf, &buf_size);
}

But it is actually not the UDRAL issue. We can either fix it on nunavut side, or write our own serialization. It might be rewritten to:

reg_udral_service_actuator_common_sp_GeneralVector_0_1_serialize_(&vector31_sp, buf, &buf_size, number_of_channels);

3. Magnetometer

In DroneCAN both autopilots use:

  • float16[3] magnetic_field_ga

Since Cyphal is based on SI, I've extended it to float32[3].

4. Barometer

In DroneCAN we use:

  • air_data.StaticPressure
  • air_data.StaticTemperature

No one uses variance for nor pressure or temperature. So, let's just use:

  • uavcan.si.unit.pressure.Scalar
  • uavcan.si.unit.temperature.Scalar

5. IMU

The DroneCAN RawImu is overloaded. I didn't see anyone use timestamp, integrated samples and covariance that makes it much more efficient. I personally would like to separate them into just raw data because I need to publish this data with rate 200+ messages/second:

  • float32[3] gyroscope
  • float32[3] accelerometer

These 2 messages uses 4 CAN-frames together while the current DroneCAN version uses 7 frames. We can even consider optimizing it to float16.

Example

Please check an example of a VTOL application based on this interface.

Please, provide your feedback.

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

Successfully merging this pull request may close these issues.

1 participant