Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduSub/mode_motordetect.cpp
Views: 1798
#include "Sub.h"1#include "stdio.h"23/*4* control_motordetect.cpp - init and run calls for motordetect flightmode;5*6* This mode pulses all thrusters to detect if they need to be reversed.7* This still requires that the user has the correct frame selected and the motors8* are connected to the correct ESCs.9*10* For each motor:11* wait until vehicle is stopped for > 500ms12* apply throttle up for 500ms13* If results are good:14* save direction and try the next motor.15* else16* wait until vehicle is stopped for > 500ms17* apply throttle down for 500ms18* If results are good19* save direction and try the next motor.20* If results are bad21* Abort!22*/2324namespace {2526// controller states27enum test_state {28STANDBY,29SETTLING,30THRUSTING,31DETECTING,32DONE33};3435enum direction {36UP = 1,37DOWN = -138};3940static uint32_t settling_timer;41static uint32_t thrusting_timer;42static uint8_t md_state;43static uint8_t current_motor;44static int16_t current_direction;45}4647bool ModeMotordetect::init(bool ignore_checks)48{49current_motor = 0;50md_state = STANDBY;51current_direction = UP;52return true;53}5455void ModeMotordetect::run()56{57// if not armed set throttle to zero and exit immediately58if (!motors.armed()) {59motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);60// Force all motors to stop61for(uint8_t i=0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {62if (motors.motor_is_enabled(i)) {63motors.output_test_num(i, 1500);64}65}66md_state = STANDBY;67return;68}6970switch(md_state) {71// Motor detection is not running, set it up to start.72case STANDBY:73current_direction = UP;74current_motor = 0;75settling_timer = AP_HAL::millis();76md_state = SETTLING;77break;7879// Wait until sub stays for 500ms not spinning and leveled.80case SETTLING:81// Force all motors to stop82for (uint8_t i=0; i <AP_MOTORS_MAX_NUM_MOTORS; i++) {83if (motors.motor_is_enabled(i)) {84motors.output_test_num(i, 1500);85}86}87// wait until gyro product is under a certain(experimental) threshold88if ((ahrs.get_gyro()*ahrs.get_gyro()) > 0.01) {89settling_timer = AP_HAL::millis();90}91// then wait 500ms more92if (AP_HAL::millis() > (settling_timer + 500)) {93md_state = THRUSTING;94thrusting_timer = AP_HAL::millis();95}9697break;9899// Thrusts motor for 500ms100case THRUSTING:101if (AP_HAL::millis() < (thrusting_timer + 500)) {102if (!motors.output_test_num(current_motor, 1500 + 300*current_direction)) {103md_state = DONE;104};105106} else {107md_state = DETECTING;108}109break;110111// Checks the result of thrusting the motor.112// Starts again at the other direction if unable to get a good reading.113// Fails if it is the second reading and it is still not good.114// Set things up to test the next motor if the reading is good.115case DETECTING:116{117// This logic results in a vector such as (1, -1, 0)118// TODO: make these thresholds parameters119Vector3f gyro = ahrs.get_gyro();120bool roll_up = gyro.x > 0.4;121bool roll_down = gyro.x < -0.4;122int roll = (int(roll_up) - int(roll_down))*current_direction;123124bool pitch_up = gyro.y > 0.4;125bool pitch_down = gyro.y < -0.4;126int pitch = (int(pitch_up) - int(pitch_down))*current_direction;127128bool yaw_up = gyro.z > 0.5;129bool yaw_down = gyro.z < -0.5;130int yaw = (+int(yaw_up) - int(yaw_down))*current_direction;131132Vector3f directions(roll, pitch, yaw);133// Good read, not inverted134if (directions == motors.get_motor_angular_factors(current_motor)) {135gcs().send_text(MAV_SEVERITY_INFO, "Thruster %d is ok!", current_motor + 1);136}137// Good read, inverted138else if (-directions == motors.get_motor_angular_factors(current_motor)) {139gcs().send_text(MAV_SEVERITY_INFO, "Thruster %d is reversed! Saving it!", current_motor + 1);140motors.set_reversed(current_motor, true);141}142// Bad read!143else {144gcs().send_text(MAV_SEVERITY_INFO, "Bad thrust read, trying to push the other way...");145// If we got here, we couldn't identify anything that made sense.146// Let's try pushing the thruster the other way, maybe we are in too shallow waters or hit something147if (current_direction == DOWN) {148// The reading for the second direction was also bad, we failed.149gcs().send_text(MAV_SEVERITY_WARNING, "Failed! Please check Thruster %d and frame setup!", current_motor + 1);150md_state = DONE;151break;152}153current_direction = DOWN;154md_state = SETTLING;155break;156}157// If we got here, we have a decent motor reading158md_state = SETTLING;159// Test the next motor, if it exists160current_motor++;161current_direction = UP;162if (!motors.motor_is_enabled(current_motor)) {163md_state = DONE;164gcs().send_text(MAV_SEVERITY_WARNING, "Motor direction detection is complete.");165}166break;167}168case DONE:169set_mode(sub.prev_control_mode, ModeReason::MISSION_END);170sub.arming.disarm(AP_Arming::Method::MOTORDETECTDONE);171break;172}173}174175176