Skip to content

Commit

Permalink
WIP
Browse files Browse the repository at this point in the history
  • Loading branch information
robertlong13 committed Nov 11, 2024
1 parent 834541b commit ed4ac65
Show file tree
Hide file tree
Showing 8 changed files with 30 additions and 28 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,7 @@ mav.log
mav.log.raw
mav.parm
mission.stg
output/
/defaults.parm
/ArduCopter/defaults.parm
/ArduPlane/defaults.parm
Expand Down
7 changes: 4 additions & 3 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1705,12 +1705,13 @@ void AP_Periph_FW::esc_telem_update()
#endif

pkt.error_count = 0;
uint16_t error_count, count;
uint32_t error_count;
uint16_t count;
if (esc_telem.get_count(i, count)) {
pkt.error_count = count;
pkt.error_count = count & 0xFF;
}
if (esc_telem.get_error_count(i, error_count)) {
pkt.error_count += (error_count & 0xFFFF) << 16;
pkt.error_count += (error_count & 0xFFFFFF) << 8;
}

uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {};
Expand Down
26 changes: 13 additions & 13 deletions Tools/Carbonix_scripts/carbonix_waf_build.sh
Original file line number Diff line number Diff line change
Expand Up @@ -6,18 +6,18 @@ set -e
echo "Running distclean..."
./waf distclean

main_boards=("CubeOrange" "CubeOrangePlus" "CubeOrange-Volanti" "CubeOrangePlus-Volanti" "CubeOrange-Ottano" "CubeOrangePlus-Ottano")
for board in "${main_boards[@]}"; do
echo "Compiling ArduPlane for $board..."
./waf configure --board "$board" -g
./waf plane
done
# main_boards=("CubeOrange" "CubeOrangePlus" "CubeOrange-Volanti" "CubeOrangePlus-Volanti" "CubeOrange-Ottano" "CubeOrangePlus-Ottano")
# for board in "${main_boards[@]}"; do
# echo "Compiling ArduPlane for $board..."
# ./waf configure --board "$board" -g
# ./waf plane
# done

periph_boards=("CarbonixF405" "CarbonixF405-no-crystal")
periph_boards=("CarbonixF405") # "CarbonixF405-no-crystal")

# Build all periph board with custom parameters
for board in "${periph_boards[@]}"; do
for file in $(find libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/ -name "*.parm"); do
for file in $(find libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/*-M* -name "*.parm"); do
# Extract the filename without the extension
filename=$(basename -- "$file")
filename="${filename%.*}"
Expand Down Expand Up @@ -45,10 +45,10 @@ for board in "${periph_boards[@]}"; do
done

# Build all Default periph board
for board in "${periph_boards[@]}"; do
echo "Compiling AP_Periph for $board..."
./waf configure --board "$board" -g
./waf AP_Periph
done
# for board in "${periph_boards[@]}"; do
# echo "Compiling AP_Periph for $board..."
# ./waf configure --board "$board" -g
# ./waf AP_Periph
# done

echo "Script completed successfully."
8 changes: 4 additions & 4 deletions libraries/AP_BLHeli/AP_BLHeli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1457,7 +1457,7 @@ void AP_BLHeli::read_telemetry_packet(void)
const uint8_t motor_idx = motor_map[last_telem_esc];
if (telem_uart->read(buf, telem_packet_size) < telem_packet_size) {
// short read, we should have all bytes ready when this function is called
increment_error_count(motor_idx - chan_offset);
// THIS LINE IS NOT ACTUALLY REACHABLE, SO WE DON'T LOG THIS (the caller already checks)
return;
}

Expand All @@ -1470,7 +1470,7 @@ void AP_BLHeli::read_telemetry_packet(void)
if (buf[telem_packet_size-1] != crc) {
// bad crc
debug("Bad CRC on %u", last_telem_esc);
increment_error_count(motor_idx - chan_offset);
increment_error_count(motor_idx - chan_offset, 1 << 16);
return;
}
// record the previous rpm so that we can slew to the new one
Expand Down Expand Up @@ -1602,7 +1602,7 @@ void AP_BLHeli::update_telemetry(void)
// if we have more than 10 bytes then we don't know which ESC
// they are from. Throw them all away
telem_uart->discard_input();
increment_error_count(motor_map[last_telem_esc] - chan_offset);
increment_error_count(motor_map[last_telem_esc] - chan_offset, 1);
return;
}
if (nbytes > 0 &&
Expand All @@ -1618,7 +1618,7 @@ void AP_BLHeli::update_telemetry(void)
if (nbytes > 0 && nbytes < telem_packet_size) {
// we've waited long enough, discard bytes if we don't have 10 yet
telem_uart->discard_input();
increment_error_count(motor_map[last_telem_esc] - chan_offset);
increment_error_count(motor_map[last_telem_esc] - chan_offset, 1 << 8);
return;
}
if (nbytes == telem_packet_size) {
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -337,7 +337,7 @@ bool AP_ESC_Telem::get_count(uint8_t esc_index, uint16_t& count) const
}

// get an individual ESC's error count if available, returns true on success
bool AP_ESC_Telem::get_error_count(uint8_t esc_index, uint16_t& error_count) const
bool AP_ESC_Telem::get_error_count(uint8_t esc_index, uint32_t& error_count) const
{
if (esc_index >= ESC_TELEM_MAX_ESCS) {
return false;
Expand Down Expand Up @@ -607,12 +607,12 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem
}

// callback to increment the error count in the frontend, should be called by the driver when an error occurs
void AP_ESC_Telem::increment_error_count(const uint8_t esc_index)
void AP_ESC_Telem::increment_error_count(const uint8_t esc_index, const uint32_t amount)
{
if (esc_index >= ESC_TELEM_MAX_ESCS) {
return;
}
_telem_data[esc_index].error_count++;
_telem_data[esc_index].error_count += amount;
}

// record an update to the RPM together with timestamp, this allows the notch values to be slewed
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class AP_ESC_Telem {
bool get_count(uint8_t esc_index, uint16_t& count) const;

// get an individual ESC's error count if available, returns true on success
bool get_error_count(uint8_t esc_index, uint16_t& error_count) const;
bool get_error_count(uint8_t esc_index, uint32_t& error_count) const;

#if AP_EXTENDED_ESC_TELEM_ENABLED
// get an individual ESC's input duty cycle if available, returns true on success
Expand Down Expand Up @@ -129,7 +129,7 @@ class AP_ESC_Telem {
void update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask);

// callback to increment the error count in the frontend, should be called by the driver when an error occurs
void increment_error_count(const uint8_t esc_index);
void increment_error_count(const uint8_t esc_index, const uint32_t amount);

#if AP_SCRIPTING_ENABLED
/*
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ void AP_ESC_Telem_Backend::update_telem_data(const uint8_t esc_index, const Tele
}

// callback to increment the error count in the frontend, should be called by the driver when an error occurs
void AP_ESC_Telem_Backend::increment_error_count(const uint8_t esc_index) {
_frontend->increment_error_count(esc_index);
void AP_ESC_Telem_Backend::increment_error_count(const uint8_t esc_index, const uint32_t amount) {
_frontend->increment_error_count(esc_index, amount);
}

/*
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class AP_ESC_Telem_Backend {
void update_telem_data(const uint8_t esc_index, const TelemetryData& new_data, const uint16_t data_present_mask);

// callback to increment the error count in the frontend, should be called by the driver when an error occurs
void increment_error_count(const uint8_t esc_index);
void increment_error_count(const uint8_t esc_index, const uint32_t amount);

private:
AP_ESC_Telem* _frontend;
Expand Down

0 comments on commit ed4ac65

Please sign in to comment.