Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -32,22 +32,24 @@
#define NERVE_COMM 1

//1. Specials board options
#define STM32H7_V2 0
#define STM32H7_V2 1

//2. Enable Flags
//* Please set/reset follwing flags according to your utility.

//2.1 Sensors
//2.1.1 IMU Sensor
#define IMU_FLAG 1
#define IMU_ICM 0
#define IMU_MPU 1
#define IMU_ICM 1
#define IMU_MPU 0
//2.1.2 Barometer Sensor
#define BARO_FLAG 1
//2.1.3 GPS Sensor
#define GPS_FLAG 1
//2.1.3 Direct Servo Control
#define SERVO_FLAG 0
#define DYNAMIXEL 1
#define KONDO 0


//2.2 State Estimate
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -211,16 +211,18 @@ void AttitudeController::pwmsControl(void)

/* nerve comm type */
#if NERVE_COMM
for(int i = 0; i < motor_number_; i++) {
#if MOTOR_TEST

if (i == (HAL_GetTick() / 2000) % motor_number_)
Spine::setMotorPwm(200, i);
else
Spine::setMotorPwm(0, i);
#else
// motor_number_ = Spine::getSlaveNum();
for(int i = 0; i < Spine::getSlaveNum(); i++) {
// #if MOTOR_TEST

// if (i == (HAL_GetTick() / 2000) % motor_number_)
// Spine::setMotorPwm(200, i);
// else
// Spine::setMotorPwm(0, i);
// #else
// Spine::setMotorPwm(target_pwm_[i] * 2000 - 1000, i);
// #endif
Spine::setMotorPwm(target_pwm_[i] * 2000 - 1000, i);
#endif
}
#endif

Expand Down Expand Up @@ -726,21 +728,14 @@ void AttitudeController::maxYawGainIndex()

void AttitudeController::pwmTestCallback(const spinal::PwmTest& pwm_msg)
{
#ifndef SIMULATION
if(pwm_msg.pwms_length && !pwm_test_flag_)
{
pwm_test_flag_ = true;
nh_->logwarn("Enter pwm test mode");
}
else if(!pwm_msg.pwms_length && pwm_test_flag_)
{
pwm_test_flag_ = false;
nh_->logwarn("Escape from pwm test mode");
return;
}

#ifndef SIMULATION
if(pwm_msg.motor_index_length)
{
if (motor_number_== 0)
{
motor_number_ = 4;
nh_->logwarn("Motor number set to 4 for test. If you want to test more motors, please perform motor arming before running the PWM test.");
}
/*Individual test mode*/
if(pwm_msg.motor_index_length != pwm_msg.pwms_length)
{
Expand All @@ -749,33 +744,59 @@ void AttitudeController::pwmTestCallback(const spinal::PwmTest& pwm_msg)
}
for(int i = 0; i < pwm_msg.motor_index_length; i++){
int motor_index = pwm_msg.motor_index[i];
/*fail safe*/
if (pwm_msg.pwms[i] >= IDLE_DUTY && pwm_msg.pwms[i] <= MAX_PWM)

/*fail safe*/
if (motor_index < motor_number_)
{
pwm_test_value_[motor_index] = pwm_msg.pwms[i];
if (IDLE_DUTY <= pwm_msg.pwms[i] && pwm_msg.pwms[i] <= MAX_PWM)
{
pwm_test_value_[motor_index] = pwm_msg.pwms[i];
}
else
{
nh_->logwarn("The value of pwm is invalid for motors");
pwm_test_value_[motor_index] = IDLE_DUTY;
}
}
else
{
nh_->logwarn("FAIL SAFE! Invaild PWM value for motor");
pwm_test_value_[motor_index] = IDLE_DUTY;
pwm_test_value_[motor_index] = std::max(IDLE_DUTY, std::min(pwm_msg.pwms[i], MAX_PWM));
}

if (!pwm_test_flag_)
{
target_pwm_[motor_index] = pwm_test_value_[motor_index];
}
}
}
else
{
/*Simultaneous test mode*/
for(int i = 0; i < MAX_MOTOR_NUMBER; i++){
/*fail safe*/
if (pwm_msg.pwms[0] >= IDLE_DUTY && pwm_msg.pwms[0] <= MAX_PWM)
{
pwm_test_value_[i] = pwm_msg.pwms[0];
}
else
{
nh_->logwarn("FAIL SAFE! Invaild PWM value for motors");
pwm_test_value_[i] = IDLE_DUTY;
if(pwm_msg.pwms_length)
{
if(!pwm_test_flag_)
{
pwm_test_flag_ = true;
nh_->logwarn("Enter pwm test mode for all motors");
}
/*Simultaneous test mode*/
for(int i = 0; i < MAX_MOTOR_NUMBER; i++){
/*fail safe*/
if (IDLE_DUTY <= pwm_msg.pwms[0] && pwm_msg.pwms[0] <= MAX_PWM)
{
pwm_test_value_[i] = pwm_msg.pwms[0];
}
else
{
nh_->logwarn("The value of pwm is invalid for motors");
pwm_test_value_[i] = IDLE_DUTY;
}
}
}
}
else if(!pwm_msg.pwms_length && pwm_test_flag_)
{
pwm_test_flag_ = false;
nh_->logwarn("Escape from pwm test mode");
}
}
#endif
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@
#define CONTROL_FEEDBACK_STATE_PUB_INTERVAL 25
#define PWM_PUB_INTERVAL 100 //100ms

#define MOTOR_TEST 0
//#define MOTOR_TEST 0

enum AXIS {
X = 0,
Expand Down