mirror of
https://github.com/YikeStone/ros_arduino_bridge.git
synced 2025-08-05 20:14:07 +05:30
Replaced all strings with F() macro in Serial.print statements
This commit is contained in:
parent
77f5963e05
commit
9a84380e7c
@ -47,7 +47,7 @@
|
|||||||
|
|
||||||
#define USE_BASE // Enable/disable the base controller code
|
#define USE_BASE // Enable/disable the base controller code
|
||||||
|
|
||||||
//#define USE_IMU // Enable/disable use of an IMU
|
#define USE_IMU // Enable/disable use of an IMU
|
||||||
|
|
||||||
/* Define the motor controller and encoder library you are using */
|
/* Define the motor controller and encoder library you are using */
|
||||||
#ifdef USE_BASE
|
#ifdef USE_BASE
|
||||||
@ -191,7 +191,7 @@ int runCommand() {
|
|||||||
|
|
||||||
switch(cmd) {
|
switch(cmd) {
|
||||||
case GET_BAUDRATE:
|
case GET_BAUDRATE:
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.println(BAUDRATE);
|
Serial.println(BAUDRATE);
|
||||||
break;
|
break;
|
||||||
case ANALOG_READ:
|
case ANALOG_READ:
|
||||||
@ -202,17 +202,17 @@ int runCommand() {
|
|||||||
break;
|
break;
|
||||||
case ANALOG_WRITE:
|
case ANALOG_WRITE:
|
||||||
analogWrite(arg1, arg2);
|
analogWrite(arg1, arg2);
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case DIGITAL_WRITE:
|
case DIGITAL_WRITE:
|
||||||
if (arg2 == 0) digitalWrite(arg1, LOW);
|
if (arg2 == 0) digitalWrite(arg1, LOW);
|
||||||
else if (arg2 == 1) digitalWrite(arg1, HIGH);
|
else if (arg2 == 1) digitalWrite(arg1, HIGH);
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case PIN_MODE:
|
case PIN_MODE:
|
||||||
if (arg2 == 0) pinMode(arg1, INPUT);
|
if (arg2 == 0) pinMode(arg1, INPUT);
|
||||||
else if (arg2 == 1) pinMode(arg1, OUTPUT);
|
else if (arg2 == 1) pinMode(arg1, OUTPUT);
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case PING:
|
case PING:
|
||||||
Serial.println(Ping(arg1));
|
Serial.println(Ping(arg1));
|
||||||
@ -221,34 +221,34 @@ int runCommand() {
|
|||||||
case READ_IMU:
|
case READ_IMU:
|
||||||
imu_data = readIMU();
|
imu_data = readIMU();
|
||||||
Serial.print(imu_data.ax);
|
Serial.print(imu_data.ax);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.ay);
|
Serial.print(imu_data.ay);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.az);
|
Serial.print(imu_data.az);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.gx);
|
Serial.print(imu_data.gx);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.gy);
|
Serial.print(imu_data.gy);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.gz);
|
Serial.print(imu_data.gz);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.mx);
|
Serial.print(imu_data.mx);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.my);
|
Serial.print(imu_data.my);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.mz);
|
Serial.print(imu_data.mz);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.roll);
|
Serial.print(imu_data.roll);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.print(imu_data.pitch);
|
Serial.print(imu_data.pitch);
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.println(imu_data.uh);
|
Serial.println(imu_data.uh);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
case SERVO_WRITE:
|
case SERVO_WRITE:
|
||||||
servos[arg1].setTargetPosition(arg2);
|
servos[arg1].setTargetPosition(arg2);
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case SERVO_READ:
|
case SERVO_READ:
|
||||||
Serial.println(servos[arg1].getServo().read());
|
Serial.println(servos[arg1].getServo().read());
|
||||||
@ -261,25 +261,25 @@ int runCommand() {
|
|||||||
myServos[arg1].enable();
|
myServos[arg1].enable();
|
||||||
nServos++;
|
nServos++;
|
||||||
}
|
}
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case SERVO_WRITE:
|
case SERVO_WRITE:
|
||||||
if (myServos[arg1].isEnabled()) {
|
if (myServos[arg1].isEnabled()) {
|
||||||
myServos[arg1].setTargetPosition(arg2);
|
myServos[arg1].setTargetPosition(arg2);
|
||||||
}
|
}
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case SERVO_READ:
|
case SERVO_READ:
|
||||||
Serial.println(myServos[arg1].getCurrentPosition());
|
Serial.println(myServos[arg1].getCurrentPosition());
|
||||||
break;
|
break;
|
||||||
case SERVO_DELAY:
|
case SERVO_DELAY:
|
||||||
myServos[arg1].setServoDelay(arg1, arg2);
|
myServos[arg1].setServoDelay(arg1, arg2);
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case DETACH_SERVO:
|
case DETACH_SERVO:
|
||||||
myServos[arg1].getServo().detach();
|
myServos[arg1].getServo().detach();
|
||||||
myServos[arg1].disable();
|
myServos[arg1].disable();
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case ATTACH_SERVO:
|
case ATTACH_SERVO:
|
||||||
if (!haveServo(arg1)) {
|
if (!haveServo(arg1)) {
|
||||||
@ -291,7 +291,7 @@ int runCommand() {
|
|||||||
myServos[arg1].getServo().attach(arg1);
|
myServos[arg1].getServo().attach(arg1);
|
||||||
}
|
}
|
||||||
myServos[arg1].enable();
|
myServos[arg1].enable();
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
@ -299,13 +299,13 @@ int runCommand() {
|
|||||||
#ifdef USE_BASE
|
#ifdef USE_BASE
|
||||||
case READ_ENCODERS:
|
case READ_ENCODERS:
|
||||||
Serial.print(readEncoder(LEFT));
|
Serial.print(readEncoder(LEFT));
|
||||||
Serial.print(" ");
|
Serial.print(F(" "));
|
||||||
Serial.println(readEncoder(RIGHT));
|
Serial.println(readEncoder(RIGHT));
|
||||||
break;
|
break;
|
||||||
case RESET_ENCODERS:
|
case RESET_ENCODERS:
|
||||||
resetEncoders();
|
resetEncoders();
|
||||||
resetPID();
|
resetPID();
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case MOTOR_SPEEDS:
|
case MOTOR_SPEEDS:
|
||||||
/* Reset the auto stop timer */
|
/* Reset the auto stop timer */
|
||||||
@ -317,7 +317,7 @@ int runCommand() {
|
|||||||
else moving = 1;
|
else moving = 1;
|
||||||
leftPID.TargetTicksPerFrame = arg1;
|
leftPID.TargetTicksPerFrame = arg1;
|
||||||
rightPID.TargetTicksPerFrame = arg2;
|
rightPID.TargetTicksPerFrame = arg2;
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
case UPDATE_PID:
|
case UPDATE_PID:
|
||||||
i = 0;
|
i = 0;
|
||||||
@ -329,11 +329,11 @@ int runCommand() {
|
|||||||
Kd = pid_args[1];
|
Kd = pid_args[1];
|
||||||
Ki = pid_args[2];
|
Ki = pid_args[2];
|
||||||
Ko = pid_args[3];
|
Ko = pid_args[3];
|
||||||
Serial.println("OK");
|
Serial.println(F("OK"));
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
default:
|
default:
|
||||||
Serial.println("Invalid Command");
|
Serial.println(F("Invalid Command"));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
x
Reference in New Issue
Block a user