Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed Adafruit_GFX BioroboticsMotorControl MODSERIAL BioroboticsEMGFilter
constants.h
00001 #pragma once 00002 00003 const double PI = 3.14159265359; 00004 // Main loop wait time per cycle. This does not influence the motor PID or EMG reading frequencies. 00005 const float main_loop_wait_time = 0.01; 00006 00007 // Time between two button polls. Used to debounce the button presses. 00008 const float button_poll_interval = 0.05; 00009 00010 const float pid_period = 0.001; // PID sample period in seconds. 00011 00012 const float emg_period = 0.005; // EMG sample period in seconds. 00013 00014 const float Kp = 10.0; 00015 const float Ki = 0.1; 00016 const float Kd = 0.5; 00017 00018 // The motor -> main gear ratio is 25 / 60. 00019 // The motor -> secondary gear ratio is 25/50 00020 const float main_gear_ratio = 25.0/60.0; 00021 const float sec_gear_ratio = 25.0/50.0; 00022 00023 const double main_motor_calibration_angle = 0.785398; // 45 degrees. 00024 const double sec_motor_calibration_angle = -0.733038; // -42 degrees. 00025 00026 const float L0 = 0.15; // Length between two motors [meter] 00027 const float L1 = 0.10; // Length first beam from right motor2 [meter] 00028 const float L2 = 0.30; // Length second beam from right motor2 [meter] 00029 const float L3 = 0.15; // Length beam between L2 and L4 [meter] 00030 const float L4 = 0.30; // Length first beam from left motor1 [meter] 00031 const float L5 = 0.35; // Length from L3 to end-effector [meter] 00032 const float L6 = 1.0; // Length beam between frame 0 and motor 1 [meter] 00033 00034 // For inverse kinematics, maximum values for angles. 00035 const float max_r_length = 0.2399; // If delta is too large the device will get stuck 00036 // Maximum and minimum angles of the main and secondary arm. 00037 const float main_arm_max_angle = 2.79253; 00038 const float main_arm_min_angle = main_motor_calibration_angle - 0.05; 00039 const float sec_arm_max_angle = 1.48353; 00040 const float sec_arm_min_angle = sec_motor_calibration_angle + 0.05;
Generated on Thu Jul 14 2022 19:50:50 by
1.7.2