mirror of
https://github.com/LinoSchmidt/RoboterArm.git
synced 2026-03-21 02:31:16 +01:00
Edited configurable Variables
This commit is contained in:
@@ -13,34 +13,45 @@
|
|||||||
#define OberarmMax 180
|
#define OberarmMax 180
|
||||||
#define OberarmMin 0
|
#define OberarmMin 0
|
||||||
|
|
||||||
#define HandMax 130
|
#define HandMax 180
|
||||||
#define HandMin 45
|
#define HandMin 95
|
||||||
|
#define HandOffPosition 180
|
||||||
|
|
||||||
#define InvertDrehung false
|
#define InvertDrehung false
|
||||||
#define InvertArm false
|
#define InvertArm true
|
||||||
#define InvertOberarm true
|
#define InvertOberarm false
|
||||||
#define InvertHand false
|
#define InvertHand false
|
||||||
|
|
||||||
#define Drehung_Start 135
|
#define Drehung_Start 135
|
||||||
#define Arm_Start 180
|
#define Arm_Start 180
|
||||||
#define Oberarm_Start 111
|
#define Oberarm_Start 111
|
||||||
#define Hand_Start 130
|
#define Hand_Start 180
|
||||||
|
|
||||||
//Joysticks
|
//Joysticks
|
||||||
#define joystick_LX_Pin 0
|
#define joystick_LX_Pin 0
|
||||||
|
#define joystick_LX_MaxSpeed 5
|
||||||
|
#define joystick_LX_MinSpeed 1
|
||||||
|
|
||||||
#define joystick_LY_Pin 1
|
#define joystick_LY_Pin 1
|
||||||
|
#define joystick_LY_MaxSpeed 5
|
||||||
|
#define joystick_LY_MinSpeed 1
|
||||||
|
|
||||||
#define joystick_RX_Pin 2
|
#define joystick_RX_Pin 2
|
||||||
|
#define joystick_RX_MaxSpeed 10
|
||||||
|
#define joystick_RX_MinSpeed 1
|
||||||
|
|
||||||
#define joystick_RY_Pin 3
|
#define joystick_RY_Pin 3
|
||||||
|
#define joystick_RY_MaxSpeed 5
|
||||||
|
#define joystick_RY_MinSpeed 1
|
||||||
|
|
||||||
#define joystick_button_Pin 8
|
#define joystick_button_Pin 8
|
||||||
|
|
||||||
#define joystick_Empfindlichkeit 4
|
#define joystick_Empfindlichkeit 4
|
||||||
#define joystick_MaxSpeed 5
|
|
||||||
#define joystick_MinSpeed 1
|
|
||||||
|
|
||||||
//Timing
|
//Timing
|
||||||
#define LoopTime 40
|
#define LoopTime 50
|
||||||
#define TimeToAutoplay 1000
|
#define TimeToAutoplay 1000
|
||||||
#define TimeToDetach 80
|
#define TimeToDetach 70
|
||||||
#define Calibration_TimeToMiddle 3000
|
#define Calibration_TimeToMiddle 3000
|
||||||
#define Calibration_messureTime 5
|
#define Calibration_messureTime 5
|
||||||
#define Calibration_messureCount 10
|
#define Calibration_messureCount 10
|
||||||
|
|||||||
@@ -211,11 +211,30 @@ void joystickButtonPress(){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void detachAttach(bool detach){
|
||||||
|
if(detach){
|
||||||
|
Drehung.detach();
|
||||||
|
Arm.detach();
|
||||||
|
Oberarm.detach();
|
||||||
|
Hand.detach();
|
||||||
|
|
||||||
|
detached = true;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
Drehung.attach(DrehungPin);
|
||||||
|
Arm.attach(ArmPin);
|
||||||
|
Oberarm.attach(OberarmPin);
|
||||||
|
Hand.attach(HandPin);
|
||||||
|
|
||||||
|
detached = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void Autoplay(){
|
void Autoplay(){
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int joystick_position(int joystick, int joystick_middle, int joystick_min, int joystick_max){
|
int joystick_position(int joystick, int joystick_middle, int joystick_min, int joystick_max, int joystick_MinSpeed, int joystick_MaxSpeed){
|
||||||
if(joystick <= joystick_middle - joystick_Empfindlichkeit)
|
if(joystick <= joystick_middle - joystick_Empfindlichkeit)
|
||||||
return(-map(joystick, joystick_middle - joystick_Empfindlichkeit, joystick_min, joystick_MinSpeed, joystick_MaxSpeed));
|
return(-map(joystick, joystick_middle - joystick_Empfindlichkeit, joystick_min, joystick_MinSpeed, joystick_MaxSpeed));
|
||||||
else if(joystick >= joystick_middle + joystick_Empfindlichkeit)
|
else if(joystick >= joystick_middle + joystick_Empfindlichkeit)
|
||||||
@@ -225,10 +244,10 @@ int joystick_position(int joystick, int joystick_middle, int joystick_min, int j
|
|||||||
}
|
}
|
||||||
|
|
||||||
void loop(){
|
void loop(){
|
||||||
joystick_LX = joystick_position(analogRead(joystick_LX_Pin), joystick_LX_middle, joystick_LX_min, joystick_LX_max);
|
joystick_LX = joystick_position(analogRead(joystick_LX_Pin), joystick_LX_middle, joystick_LX_min, joystick_LX_max, joystick_LX_MinSpeed, joystick_LX_MaxSpeed);
|
||||||
joystick_LY = joystick_position(analogRead(joystick_LY_Pin), joystick_LY_middle, joystick_LY_min, joystick_LY_max);
|
joystick_LY = joystick_position(analogRead(joystick_LY_Pin), joystick_LY_middle, joystick_LY_min, joystick_LY_max, joystick_LY_MinSpeed, joystick_LY_MaxSpeed);
|
||||||
joystick_RX = joystick_position(analogRead(joystick_RX_Pin), joystick_RX_middle, joystick_RX_min, joystick_RX_max);
|
joystick_RX = joystick_position(analogRead(joystick_RX_Pin), joystick_RX_middle, joystick_RX_min, joystick_RX_max, joystick_RX_MinSpeed, joystick_RX_MaxSpeed);
|
||||||
joystick_RY = joystick_position(analogRead(joystick_RY_Pin), joystick_RY_middle, joystick_RY_min, joystick_RY_max);
|
joystick_RY = joystick_position(analogRead(joystick_RY_Pin), joystick_RY_middle, joystick_RY_min, joystick_RY_max, joystick_RY_MinSpeed, joystick_RY_MaxSpeed);
|
||||||
|
|
||||||
if(joystick_LX == 0 && joystick_LY == 0 && joystick_RX == 0 && joystick_RY == 0){
|
if(joystick_LX == 0 && joystick_LY == 0 && joystick_RX == 0 && joystick_RY == 0){
|
||||||
if (TimeToAutoplay > offtime)
|
if (TimeToAutoplay > offtime)
|
||||||
@@ -237,12 +256,7 @@ void loop(){
|
|||||||
else{
|
else{
|
||||||
offtime = 0;
|
offtime = 0;
|
||||||
if(detached){
|
if(detached){
|
||||||
Drehung.attach(DrehungPin);
|
detachAttach(false);
|
||||||
Arm.attach(ArmPin);
|
|
||||||
Oberarm.attach(OberarmPin);
|
|
||||||
Hand.attach(HandPin);
|
|
||||||
|
|
||||||
detached = false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if(joystick_LX != 0){
|
if(joystick_LX != 0){
|
||||||
@@ -283,22 +297,11 @@ void loop(){
|
|||||||
Autoplay();
|
Autoplay();
|
||||||
}
|
}
|
||||||
else if(offtime >= TimeToDetach){
|
else if(offtime >= TimeToDetach){
|
||||||
Drehung.detach();
|
detachAttach(true);
|
||||||
Arm.detach();
|
|
||||||
Oberarm.detach();
|
|
||||||
Hand.detach();
|
|
||||||
|
|
||||||
detached = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if(digitalRead(joystick_button_Pin) == LOW){
|
if(digitalRead(joystick_button_Pin) == LOW){
|
||||||
Drehung.detach();
|
detachAttach(true);
|
||||||
Arm.detach();
|
|
||||||
Oberarm.detach();
|
|
||||||
Hand.detach();
|
|
||||||
|
|
||||||
detached = true;
|
|
||||||
|
|
||||||
joystickButtonPress();
|
joystickButtonPress();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user