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

T-Motor Alpha ESC telemetry input support #19666

1 change: 1 addition & 0 deletions Tools/ardupilotwaf/ardupilotwaf.py
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@
'AP_VideoTX',
'AP_FETtecOneWire',
'AP_Torqeedo',
'AP_TMotorESC',
]

def get_legacy_defines(sketch_name, bld):
Expand Down
26 changes: 25 additions & 1 deletion libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <AP_OSD/AP_OSD.h>
#include <AP_Button/AP_Button.h>
#include <AP_FETtecOneWire/AP_FETtecOneWire.h>
#include <AP_TMotorESC/AP_TMotorESC.h>

#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#include <AP_CANManager/AP_CANManager.h>
Expand Down Expand Up @@ -1106,7 +1107,7 @@ bool AP_Arming::fettec_checks(bool display_failure) const
return true;
}

// check camera is ready
// check ESCs are ready
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
if (!f->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
check_failed(ARMING_CHECK_ALL, display_failure, "FETtec: %s", fail_msg);
Expand All @@ -1116,6 +1117,24 @@ bool AP_Arming::fettec_checks(bool display_failure) const
return true;
}

bool AP_Arming::tmotor_esc_checks(bool display_failure) const
{
#if AP_TMOTOR_ESC_ENABLED
const AP_TMotorESC *f = AP_TMotorESC::get_singleton();
if (f == nullptr) {
return true;
}

// check ESCs are ready
char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
if (!f->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
check_failed(ARMING_CHECK_ALL, display_failure, "TMotor: %s", fail_msg);
return false;
}
#endif
return true;
}

// request an auxiliary authorisation id. This id should be used in subsequent calls to set_aux_auth_passed/failed
// returns true on success
bool AP_Arming::get_aux_auth_id(uint8_t& auth_id)
Expand Down Expand Up @@ -1280,7 +1299,12 @@ bool AP_Arming::pre_arm_checks(bool report)
& proximity_checks(report)
& camera_checks(report)
& osd_checks(report)
#if AP_FETTEC_ONEWIRE_ENABLED
& fettec_checks(report)
#endif
#if AP_TMOTOR_ESC_ENABLED
& tmotor_esc_checks(report)
#endif
& visodom_checks(report)
& aux_auth_checks(report)
& disarm_switch_checks(report)
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Arming/AP_Arming.h
Original file line number Diff line number Diff line change
Expand Up @@ -188,6 +188,8 @@ class AP_Arming {

bool fettec_checks(bool display_failure) const;

bool tmotor_esc_checks(bool display_failure) const;

virtual bool proximity_checks(bool report) const;

bool servo_checks(bool report) const;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ void AP_FETtecOneWire::init()

// initialise ESC ids. This enforces that the FETtec ESC ids
// inside FETtec ESCs need to be contiguous and start at ID 1
// which required by fast-throttle commands.
// which is required by fast-throttle commands.
uint8_t esc_offset = 0; // offset into our device-driver dynamically-allocated array of ESCs
uint8_t esc_id = 1; // ESC ids inside FETtec protocol are one-indexed
uint8_t servo_chan_offset = 0; // offset into _motor_mask_parameter array
Expand Down
18 changes: 9 additions & 9 deletions libraries/AP_FETtecOneWire/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ FETtec OneWire is an [ESC](https://en.wikipedia.org/wiki/Electronic_speed_contro
It is a (bidirectional) [digital full-duplex asynchronous serial communication protocol](https://en.wikipedia.org/wiki/Asynchronous_serial_communication) running at 500Kbit/s Baudrate. It requires three wire (RX, TX and GND) connection (albeit the name OneWire) regardless of the number of ESCs connected.
Unlike bidirectional-Dshot, the FETtec OneWire protocol does not need one DMA channel per ESC for bidirectional communication.

For purchase, connection and configuration information please see the [Ardupilot FETtec OneWire wiki page](https://ardupilot.org/copter/docs/common-fettec-onewire.html).
For purchase, connection and configuration information please see the [ArduPilot FETtec OneWire wiki page](https://ardupilot.org/copter/docs/common-fettec-onewire.html).

## Features of this device driver

Expand Down Expand Up @@ -39,9 +39,9 @@ For purchase, connection and configuration information please see the [Ardupilot
- fly a copter over a simulated serial link connection


## Ardupilot to ESC protocol
## ArduPilot to ESC protocol

The FETtec OneWire protocol supports up to 24 ESCs. As most copters only use at most 12 motors, Ardupilot's implementation supports only 12 (`ESC_TELEM_MAX_ESCS`)to save memory.
The FETtec OneWire protocol supports up to 24 ESCs. As most copters only use at most 12 motors, ArduPilot's implementation supports only 12 (`ESC_TELEM_MAX_ESCS`)to save memory.

There are two types of messages sent to the ESCs configuration and fast-throttle messages:

Expand Down Expand Up @@ -95,21 +95,21 @@ The signal is used to transfer the eleven bit throttle signals with as few bytes
All motors wait for the complete message with all throttle signals before changing their output.

If telemetry is requested the ESCs will answer them in the ESC-ID order.
See *ESC to Ardupilot Protocol* section below and comments in `AP_FETtecOneWire.cpp` for details.
See *ESC to ArduPilot Protocol* section below and comments in `AP_FETtecOneWire.cpp` for details.


### Timing

Four ESCs need 90us for the fast-throttle request and telemetry reception. With four ESCs 11kHz update would be possible.
Each additional ESC adds 11 extra fast-throttle command bits, so the update rate is lowered by each additional ESC.
If you use 8 ESCs, it needs 160us including telemetry response, so 5.8kHz update rate would be possible.
The FETtec Ardupilot device driver limits the message transmit period to `_min_fast_throttle_period_us` according to the number of ESCs used.
The FETtec ArduPilot device driver limits the message transmit period to `_min_fast_throttle_period_us` according to the number of ESCs used.
The update() function has an extra invocation period limit so that even at very high loop rates the the ESCs will still operate correctly albeit doing some decimation.
The current update rate for Copter is 400Hz (~2500us) and for other vehicles is 50Hz (~20000us) so we are bellow device driver limit.

**Note:** The FETtec ESCs firmware requires at least a 4Hz fast-throttle update rate (max. 250ms between messages) otherwise the FETtec ESC disarm (stop) the motors.

## ESC to Ardupilot protocol
## ESC to ArduPilot protocol

OneWire ESC telemetry information is sent back to the autopilot:

Expand All @@ -120,7 +120,7 @@ OneWire ESC telemetry information is sent back to the autopilot:
- Temperature (°C/10)
- CRC errors (ArduPilot->ESC) counter

This information is used by Ardupilot to:
This information is used by ArduPilot to:

- log the status of each ESC to the SDCard or internal Flash, for post flight analysis
- send the status of each ESC to the ground station or companion computer for real-time monitoring
Expand All @@ -137,8 +137,8 @@ The data is forwarded to the `AP_ESC_Telem` class that distributes it to other p

There are two public top level functions `update()` and `pre_arm_check()`.
And these two call all other private internal functions.
A single (per ESC) state variable (`_escs[i]._state`) is used in both the RX and TX state machnines.
Here is the callgraph:
A single (per ESC) state variable (`_escs[i]._state`) is used in both the RX and TX state machines.
Here is the call graph:

```
update()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -135,3 +135,4 @@ define HAL_BARO_20789_I2C_ADDR_PRESS 0x63
# Disable un-needed hardware drivers
define HAL_WITH_ESC_TELEM 0
define AP_FETTEC_ONEWIRE_ENABLED 0
define AP_TMOTOR_ESC_ENABLED 0
1 change: 1 addition & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -138,3 +138,4 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 8192
# Disable un-needed hardware drivers
define HAL_WITH_ESC_TELEM 0
define AP_FETTEC_ONEWIRE_ENABLED 0
define AP_TMOTOR_ESC_ENABLED 0
1 change: 1 addition & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -68,3 +68,4 @@ env BUILD_ABIN True
# Disable un-needed hardware drivers
define HAL_WITH_ESC_TELEM 0
define AP_FETTEC_ONEWIRE_ENABLED 0
define AP_TMOTOR_ESC_ENABLED 0
2 changes: 1 addition & 1 deletion libraries/AP_SerialManager/AP_SerialManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 1_PROTOCOL
// @DisplayName: Telem1 protocol selection
// @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41: TMotorESC
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2),
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_SerialManager/AP_SerialManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,7 @@ class AP_SerialManager {
SerialProtocol_AIS = 40,
SerialProtocol_CoDevESC = 41,
SerialProtocol_MSP_DisplayPort = 42,
SerialProtocol_TMotorESC = 43,
SerialProtocol_NumProtocols // must be the last value
};

Expand Down
Loading