Added flos hall #10
@ -97,6 +97,34 @@ add_custom_command(OUTPUT motortest.bin COMMAND arm-none-eabi-objcopy -O binary
|
|||||||
add_custom_target(motortest ALL SOURCES motortest.hex motortest.bin)
|
add_custom_target(motortest ALL SOURCES motortest.hex motortest.bin)
|
||||||
add_custom_target(flash-motortest COMMAND st-flash --reset write motortest.bin 0x8000000 SOURCES motortest.bin DEPENDS motortest.bin)
|
add_custom_target(flash-motortest COMMAND st-flash --reset write motortest.bin 0x8000000 SOURCES motortest.bin DEPENDS motortest.bin)
|
||||||
|
|
||||||
|
#
|
||||||
|
# motor test peter
|
||||||
|
#
|
||||||
|
add_executable(motortest_peter.elf config.h defines.h main.cpp)
|
||||||
|
target_link_libraries(motortest_peter.elf stm32_hal emanuel_foc_model bobbycar-protocol)
|
||||||
|
target_compile_options(motortest_peter.elf PRIVATE
|
||||||
|
-DMOTOR_TEST
|
||||||
|
-DFEATURE_IGNORE_OTHER_MOTOR
|
||||||
|
# -DGSCHISSENES_HALL
|
||||||
|
-DSEHR_GSCHISSENES_HALL
|
||||||
|
# -DGSCHISSENE_PWM_FREQ
|
||||||
|
# -DFEATURE_BUTTON
|
||||||
|
-DPETERS_PLATINE
|
||||||
|
# -DHUARN2
|
||||||
|
# -DHUARN3
|
||||||
|
# -DFEATURE_SERIAL_CONTROL
|
||||||
|
# -DFEATURE_SERIAL_FEEDBACK
|
||||||
|
# -DLOG_TO_SERIAL
|
||||||
|
# -DFEATURE_CAN
|
||||||
|
# -DCAN_LOG_UNKNOWN_ADDR
|
||||||
|
# -DIS_BACK
|
||||||
|
)
|
||||||
|
add_custom_command(OUTPUT motortest_peter.hex COMMAND arm-none-eabi-objcopy -O ihex motortest_peter.elf motortest_peter.hex DEPENDS motortest_peter.elf)
|
||||||
|
add_custom_command(OUTPUT motortest_peter.bin COMMAND arm-none-eabi-objcopy -O binary -S motortest_peter.elf motortest_peter.bin DEPENDS motortest_peter.elf)
|
||||||
|
add_custom_target(motortest_peter ALL SOURCES motortest_peter.hex motortest_peter.bin)
|
||||||
|
add_custom_target(flash-motortest_peter COMMAND st-flash --reset write motortest_peter.bin 0x8000000 SOURCES motortest_peter.bin DEPENDS motortest_peter.bin)
|
||||||
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# feedc0de front
|
# feedc0de front
|
||||||
#
|
#
|
||||||
|
50
defines.h
50
defines.h
@ -23,29 +23,37 @@
|
|||||||
#include "stm32f1xx_hal.h"
|
#include "stm32f1xx_hal.h"
|
||||||
|
|
||||||
#ifdef PETERS_PLATINE
|
#ifdef PETERS_PLATINE
|
||||||
#ifdef GSCHISSENES_HALL
|
#ifdef GSCHISSENES_HALL
|
||||||
#define LEFT_HALL_U_PIN GPIO_PIN_10
|
#define LEFT_HALL_U_PIN GPIO_PIN_10
|
||||||
#define LEFT_HALL_V_PIN GPIO_PIN_11
|
#define LEFT_HALL_V_PIN GPIO_PIN_11
|
||||||
#define LEFT_HALL_W_PIN GPIO_PIN_12
|
#define LEFT_HALL_W_PIN GPIO_PIN_12
|
||||||
#else
|
#elif SEHR_GSCHISSENES_HALL
|
||||||
#define LEFT_HALL_U_PIN GPIO_PIN_12
|
#define LEFT_HALL_U_PIN GPIO_PIN_12
|
||||||
#define LEFT_HALL_V_PIN GPIO_PIN_11
|
#define LEFT_HALL_V_PIN GPIO_PIN_10
|
||||||
#define LEFT_HALL_W_PIN GPIO_PIN_10
|
#define LEFT_HALL_W_PIN GPIO_PIN_11
|
||||||
#endif
|
#else
|
||||||
|
#define LEFT_HALL_U_PIN GPIO_PIN_12
|
||||||
|
#define LEFT_HALL_V_PIN GPIO_PIN_11
|
||||||
|
#define LEFT_HALL_W_PIN GPIO_PIN_10
|
||||||
|
#endif
|
||||||
|
|
||||||
#define LEFT_HALL_U_PORT GPIOC
|
#define LEFT_HALL_U_PORT GPIOC
|
||||||
#define LEFT_HALL_V_PORT GPIOC
|
#define LEFT_HALL_V_PORT GPIOC
|
||||||
#define LEFT_HALL_W_PORT GPIOC
|
#define LEFT_HALL_W_PORT GPIOC
|
||||||
|
|
||||||
#ifdef GSCHISSENES_HALL
|
#ifdef GSCHISSENES_HALL
|
||||||
#define RIGHT_HALL_U_PIN GPIO_PIN_7
|
#define RIGHT_HALL_U_PIN GPIO_PIN_7
|
||||||
#define RIGHT_HALL_V_PIN GPIO_PIN_6
|
#define RIGHT_HALL_V_PIN GPIO_PIN_6
|
||||||
#define RIGHT_HALL_W_PIN GPIO_PIN_5
|
#define RIGHT_HALL_W_PIN GPIO_PIN_5
|
||||||
#else
|
#elif SEHR_GSCHISSENES_HALL
|
||||||
#define RIGHT_HALL_U_PIN GPIO_PIN_5
|
#define RIGHT_HALL_U_PIN GPIO_PIN_5
|
||||||
#define RIGHT_HALL_V_PIN GPIO_PIN_6
|
#define RIGHT_HALL_V_PIN GPIO_PIN_7
|
||||||
#define RIGHT_HALL_W_PIN GPIO_PIN_7
|
#define RIGHT_HALL_W_PIN GPIO_PIN_6
|
||||||
#endif
|
#else
|
||||||
|
#define RIGHT_HALL_U_PIN GPIO_PIN_5
|
||||||
|
#define RIGHT_HALL_V_PIN GPIO_PIN_6
|
||||||
|
#define RIGHT_HALL_W_PIN GPIO_PIN_7
|
||||||
|
#endif
|
||||||
|
|
||||||
#define RIGHT_HALL_U_PORT GPIOB
|
#define RIGHT_HALL_U_PORT GPIOB
|
||||||
#define RIGHT_HALL_V_PORT GPIOB
|
#define RIGHT_HALL_V_PORT GPIOB
|
||||||
|
30
main.cpp
30
main.cpp
@ -516,7 +516,7 @@ void updateMotors()
|
|||||||
/* Make sure to stop BOTH motors in case of an error */
|
/* Make sure to stop BOTH motors in case of an error */
|
||||||
|
|
||||||
constexpr bool ignoreOtherMotor =
|
constexpr bool ignoreOtherMotor =
|
||||||
#ifdef FEATURE_IGNORE_OTHER_MOTOR
|
#ifndef FEATURE_IGNORE_OTHER_MOTOR
|
||||||
false
|
false
|
||||||
#else
|
#else
|
||||||
true
|
true
|
||||||
@ -1390,8 +1390,8 @@ void doMotorTest()
|
|||||||
|
|
||||||
left.enable = true;
|
left.enable = true;
|
||||||
left.rtU.r_inpTgt = pwm;
|
left.rtU.r_inpTgt = pwm;
|
||||||
left.rtP.z_ctrlTypSel = uint8_t(ControlType::FieldOrientedControl);
|
left.rtP.z_ctrlTypSel = uint8_t(ControlType::Sinusoidal);
|
||||||
left.rtU.z_ctrlModReq = uint8_t(ControlMode::Speed);
|
left.rtU.z_ctrlModReq = uint8_t(ControlMode::Voltage);
|
||||||
left.rtP.i_max = (2 * A2BIT_CONV) << 4;
|
left.rtP.i_max = (2 * A2BIT_CONV) << 4;
|
||||||
left.iDcMax = 4;
|
left.iDcMax = 4;
|
||||||
left.rtP.n_max = 1000 << 4;
|
left.rtP.n_max = 1000 << 4;
|
||||||
@ -1399,9 +1399,9 @@ void doMotorTest()
|
|||||||
left.rtP.a_phaAdvMax = 40 << 4;
|
left.rtP.a_phaAdvMax = 40 << 4;
|
||||||
|
|
||||||
right.enable = true;
|
right.enable = true;
|
||||||
right.rtU.r_inpTgt = pwm;
|
right.rtU.r_inpTgt = -pwm;
|
||||||
right.rtP.z_ctrlTypSel = uint8_t(ControlType::FieldOrientedControl);
|
right.rtP.z_ctrlTypSel = uint8_t(ControlType::Sinusoidal);
|
||||||
right.rtU.z_ctrlModReq = uint8_t(ControlMode::Speed);
|
right.rtU.z_ctrlModReq = uint8_t(ControlMode::Voltage);
|
||||||
right.rtP.i_max = (2 * A2BIT_CONV) << 4;
|
right.rtP.i_max = (2 * A2BIT_CONV) << 4;
|
||||||
right.iDcMax = 4;
|
right.iDcMax = 4;
|
||||||
right.rtP.n_max = 1000 << 4;
|
right.rtP.n_max = 1000 << 4;
|
||||||
@ -1418,6 +1418,24 @@ void doMotorTest()
|
|||||||
pwm = -pwmMax;
|
pwm = -pwmMax;
|
||||||
dir = 1;
|
dir = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if(left.rtY.z_errCode != 0 || right.rtY.z_errCode != 0) {
|
||||||
|
if(left.rtY.z_errCode == 0 && right.rtY.z_errCode != 0) { //rechts
|
||||||
|
buzzer.freq = 1;
|
||||||
|
buzzer.pattern = 1;
|
||||||
|
}
|
||||||
|
if(right.rtY.z_errCode == 0 && left.rtY.z_errCode != 0) { //links
|
||||||
|
buzzer.freq = 3;
|
||||||
|
buzzer.pattern = 3;
|
||||||
|
}
|
||||||
|
if(right.rtY.z_errCode != 0 && left.rtY.z_errCode != 0) { //beide
|
||||||
|
buzzer.freq = 5;
|
||||||
|
buzzer.pattern = 5;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
buzzer.freq = 0;
|
||||||
|
buzzer.pattern = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Reference in New Issue
Block a user