使用 PROGMEM 以降低内存占用

This commit is contained in:
lxbpxylps@126.com 2021-03-25 13:40:18 +08:00
parent 11e34760eb
commit 14c19baf73
6 changed files with 106 additions and 106 deletions

View File

@ -70,7 +70,7 @@ Radio radio; //通讯实例
//****************************************全局变量****************************************
//GND Pins
uint8_t gnd_pins[8] = {14, 15, 32, 33, 34, 35, 36, 37};
const uint8_t gnd_pins[8] PROGMEM = {14, 15, 32, 33, 34, 35, 36, 37};
//EEPROM 储存的调试数据
struct StroageInfo
@ -190,14 +190,14 @@ int loop_time = 0;
//错误消息函数,用于在出现致命错误后结束程序
void DebugCanNotContinue(char* message)
{
NeoSerial.print("#TAICHI: CAN NOT CONTINUE WHEN "); NeoSerial.println(message);
NeoSerial.print("#TAICHI: loop_time: "); NeoSerial.println(loop_time);
NeoSerial.print("#TAICHI: pass: ["); NeoSerial.print(passed_point.x); NeoSerial.print(", "); NeoSerial.print(passed_point.y); NeoSerial.print("]");
NeoSerial.print(" TYPE: "); NeoSerial.println((int)passed_point.type);
NeoSerial.print("#TAICHI: next: ["); NeoSerial.print(next_point.x); NeoSerial.print(", "); NeoSerial.print(next_point.y); NeoSerial.print("]");
NeoSerial.print(" next_position: "); NeoSerial.print((int)next_position);
NeoSerial.print(" TYPE: "); NeoSerial.println((int)next_point.type);
NeoSerial.print("#TAICHI: is_claw_catch: "); NeoSerial.print((int)is_claw_catch); NeoSerial.print(" is_claw_ok: "); NeoSerial.println((int)is_claw_ok);
NeoSerial.print(F("#TAICHI: CAN NOT CONTINUE WHEN ")); NeoSerial.println(message);
NeoSerial.print(F("#TAICHI: loop_time: ")); NeoSerial.println(loop_time);
NeoSerial.print(F("#TAICHI: pass: [")); NeoSerial.print(passed_point.x); NeoSerial.print(F(", ")); NeoSerial.print(passed_point.y); NeoSerial.print(F("]"));
NeoSerial.print(F(" TYPE: ")); NeoSerial.println((int)passed_point.type);
NeoSerial.print(F("#TAICHI: next: [")); NeoSerial.print(next_point.x); NeoSerial.print(F(", ")); NeoSerial.print(next_point.y); NeoSerial.print(F("]"));
NeoSerial.print(F(" next_position: ")); NeoSerial.print((int)next_position);
NeoSerial.print(F(" TYPE: ")); NeoSerial.println((int)next_point.type);
NeoSerial.print(F("#TAICHI: is_claw_catch: ")); NeoSerial.print((int)is_claw_catch); NeoSerial.print(F(" is_claw_ok: ")); NeoSerial.println((int)is_claw_ok);
SRamDisplay();
while (1) {}
@ -210,7 +210,7 @@ void setup()
{
#ifdef TAICHI_DEBUG
NeoSerial.begin(DEBUG_BAUT_RATE);
NeoSerial.println("#TAICHI: ======================setup()=====================");
NeoSerial.println(F("#TAICHI: ======================setup()====================="));
SRamDisplay();
#endif
@ -248,14 +248,14 @@ void loop()
#ifdef TAICHI_DEBUG
loop_time++;
NeoSerial.println("#TAICHI: ====================New loop()====================");
NeoSerial.print("#TAICHI: loop_time: "); NeoSerial.println(loop_time);
NeoSerial.print("#TAICHI: pass: ["); NeoSerial.print(passed_point.x); NeoSerial.print(", "); NeoSerial.print(passed_point.y); NeoSerial.print("]");
NeoSerial.print(" TYPE: "); NeoSerial.println((int)passed_point.type);
NeoSerial.print("#TAICHI: next: ["); NeoSerial.print(next_point.x); NeoSerial.print(", "); NeoSerial.print(next_point.y); NeoSerial.print("]");
NeoSerial.print(" next_position: "); NeoSerial.print((int)next_position);
NeoSerial.print(" TYPE: "); NeoSerial.println((int)next_point.type);
NeoSerial.print("#TAICHI: is_claw_catch: "); NeoSerial.print((int)is_claw_catch); NeoSerial.print(" is_claw_ok: "); NeoSerial.println((int)is_claw_ok);
NeoSerial.println(F("#TAICHI: ====================New loop()===================="));
NeoSerial.print(F("#TAICHI: loop_time: ")); NeoSerial.println(loop_time);
NeoSerial.print(F("#TAICHI: pass: [")); NeoSerial.print(passed_point.x); NeoSerial.print(F(", ")); NeoSerial.print(passed_point.y); NeoSerial.print(F("]"));
NeoSerial.print(F(" TYPE: ")); NeoSerial.println((int)passed_point.type);
NeoSerial.print(F("#TAICHI: next: [")); NeoSerial.print(next_point.x); NeoSerial.print(F(", ")); NeoSerial.print(next_point.y); NeoSerial.print(F("]"));
NeoSerial.print(F(" next_position: ")); NeoSerial.print((int)next_position);
NeoSerial.print(F(" TYPE: ")); NeoSerial.println((int)next_point.type);
NeoSerial.print(F("#TAICHI: is_claw_catch: ")); NeoSerial.print((int)is_claw_catch); NeoSerial.print(F(" is_claw_ok: ")); NeoSerial.println((int)is_claw_ok);
SRamDisplay();
#endif
@ -488,7 +488,7 @@ void loop()
route.UpdatePosition();
#ifdef TAICHI_DEBUG
NeoSerial.println("#TAICHI: ====================End loop()====================");
NeoSerial.println(F("#TAICHI: ====================End loop()===================="));
#endif
}
@ -529,17 +529,17 @@ void ReadFromEEPROM(void)
delay_time_after_turn = stroage_info.delay_time_after_turn;
#ifdef TAICHI_DEBUG
NeoSerial.println("#TAICHI: Data based on EEPROM : ");
NeoSerial.print("north_left_angle: "); NeoSerial.println(north_left_angle);
NeoSerial.print("north_right_angle: "); NeoSerial.println(north_right_angle);
NeoSerial.print("west_left_angle: "); NeoSerial.println(west_left_angle);
NeoSerial.print("west_right_angle: "); NeoSerial.println(west_right_angle);
NeoSerial.print("south_left_angle: "); NeoSerial.println(south_left_angle);
NeoSerial.print("south_right_angle: "); NeoSerial.println(south_right_angle);
NeoSerial.print("east_left_angle: "); NeoSerial.println(east_left_angle);
NeoSerial.print("east_right_angle: "); NeoSerial.println(east_right_angle);
NeoSerial.print("gray_7_gate: "); NeoSerial.println(stroage_info.gray_7_gate);
NeoSerial.print("delay_time_after_turn: "); NeoSerial.println(delay_time_after_turn);
NeoSerial.println(F("#TAICHI: Data based on EEPROM : "));
NeoSerial.print(F("north_left_angle: ")); NeoSerial.println(north_left_angle);
NeoSerial.print(F("north_right_angle: ")); NeoSerial.println(north_right_angle);
NeoSerial.print(F("west_left_angle: ")); NeoSerial.println(west_left_angle);
NeoSerial.print(F("west_right_angle: ")); NeoSerial.println(west_right_angle);
NeoSerial.print(F("south_left_angle: ")); NeoSerial.println(south_left_angle);
NeoSerial.print(F("south_right_angle: ")); NeoSerial.println(south_right_angle);
NeoSerial.print(F("east_left_angle: ")); NeoSerial.println(east_left_angle);
NeoSerial.print(F("east_right_angle: ")); NeoSerial.println(east_right_angle);
NeoSerial.print(F("gray_7_gate: ")); NeoSerial.println(stroage_info.gray_7_gate);
NeoSerial.print(F("delay_time_after_turn: ")); NeoSerial.println(delay_time_after_turn);
#endif
}
@ -571,7 +571,7 @@ void CheckGrayStatus(void)
}
#ifdef TAICHI_DEBUG
NeoSerial.println("#TAICHI: Gray Sensor Status OK!");
NeoSerial.println(F("#TAICHI: Gray Sensor Status OK!"));
#endif
}
@ -685,8 +685,8 @@ void LineForward(uint8_t end_position, float speed_rate)
{
#ifdef TAICHI_DEBUG
//调试输出沿线直行状态
NeoSerial.print("#TAICHI: Line Forward");
NeoSerial.print(" end_position: ");
NeoSerial.print(F("#TAICHI: Line Forward"));
NeoSerial.print(F(" end_position: "));
NeoSerial.println((int)end_position);
#endif
@ -749,7 +749,7 @@ void LineForward(uint8_t end_position, float speed_rate)
#ifdef TAICHI_DEBUG
//调试输出沿线直行结束
NeoSerial.println("#TAICHI: End Line Forward");
NeoSerial.println(F("#TAICHI: End Line Forward"));
#endif
}
@ -759,8 +759,8 @@ void LineBackward(uint8_t end_position, float speed_rate)
{
#ifdef TAICHI_DEBUG
//调试输出沿线后退状态
NeoSerial.print("#TAICHI: Line Backward");
NeoSerial.print(" end_position: ");
NeoSerial.print(F("#TAICHI: Line Backward"));
NeoSerial.print(F(" end_position: "));
NeoSerial.println((int)end_position);
#endif
@ -811,7 +811,7 @@ void LineBackward(uint8_t end_position, float speed_rate)
#ifdef TAICHI_DEBUG
//调试输出沿线后退结束
NeoSerial.println("#TAICHI: End Line Backward");
NeoSerial.println(F("#TAICHI: End Line Backward"));
#endif
}
@ -830,7 +830,7 @@ void TurnDirection(float speed_rate)
#ifdef TAICHI_DEBUG
//调试输出直行或后退或转向状态
NeoSerial.println("#TAICHI: JUMP THE RELEASE/GETOUT/GAIN POINT FOR STATUS REASON");
NeoSerial.println(F("#TAICHI: JUMP THE RELEASE/GETOUT/GAIN POINT FOR STATUS REASON"));
#endif
}
@ -838,8 +838,8 @@ void TurnDirection(float speed_rate)
#ifdef TAICHI_DEBUG
//调试输出直行或后退或转向状态
NeoSerial.print("#TAICHI: Turn Direction");
NeoSerial.print(" direction: ");
NeoSerial.print(F("#TAICHI: Turn Direction"));
NeoSerial.print(F(" direction: "));
NeoSerial.println((int)direction);
#endif
@ -918,7 +918,7 @@ void TurnDirection(float speed_rate)
#ifdef TAICHI_DEBUG
//调试输出直行或后退或转向结束
NeoSerial.println("#TAICHI: End Turn Direction");
NeoSerial.println(F("#TAICHI: End Turn Direction"));
#endif
}
@ -949,12 +949,12 @@ bool CatchAndCheck(uint8_t type, float speed)
while (millis() - begin_time < catch_delay_time)
{
#ifndef DISABLE_CLAW_CHECK
if (sensor.IsPushed(BUTTON_1)) //开关 1 闭合,即爪子两端接触,说明抓取失败
if (sensor.IsPushed(BUTTON_2)) //开关 2 闭合,即爪子两端接触,说明抓取失败
{
#ifdef TAICHI_DEBUG
//调试输出失败信息
NeoSerial.print("#TAICHI: **********FAIL CATCH!**********");
NeoSerial.print(" catch_times: "); NeoSerial.println((int)catch_times);
NeoSerial.print(F("#TAICHI: **********FAIL CATCH!**********"));
NeoSerial.print(F(" catch_times: ")); NeoSerial.println((int)catch_times);
#endif
if (type == CATCH_TYPE_GAIN)
@ -988,14 +988,14 @@ bool CatchAndCheck(uint8_t type, float speed)
#ifndef DISABLE_CLAW_CHECK
#ifdef TAICHI_DEBUG
//调试输出成功信息
NeoSerial.println("#TAICHI: SUCCESS CATCH!");
NeoSerial.println(F("#TAICHI: SUCCESS CATCH!"));
#endif
#endif
#ifdef DISABLE_CLAW_CHECK
#ifdef TAICHI_DEBUG
//调试输出结束信息
NeoSerial.println("#TAICHI: CATCH WITHOUT CHECK!");
NeoSerial.println(F("#TAICHI: CATCH WITHOUT CHECK!"));
#endif
#endif
@ -1010,7 +1010,7 @@ bool OpenClawAndCheck(void)
#ifdef DISABLE_CLAW_CHECK
#ifdef TAICHI_DEBUG
//调试输出信息
NeoSerial.println("#TAICHI: DISABLE CLAW CHECK!");
NeoSerial.println(F("#TAICHI: DISABLE CLAW CHECK!"));
#endif
is_claw_ok = true;
@ -1026,11 +1026,11 @@ bool OpenClawAndCheck(void)
//等待完成动作
while (millis() - begin_time < CLAW_OPEN_USE_TIME)
{
if (!sensor.IsPushed(BUTTON_1)) //开关 1 打开,即爪子两端脱离接触,说明打开爪子成功
if (!sensor.IsPushed(BUTTON_2)) //开关 2 打开,即爪子两端脱离接触,说明打开爪子成功
{
#ifdef TAICHI_DEBUG
//调试输出成功信息
NeoSerial.println("#TAICHI: SUCCESS OPEN CLAW!");
NeoSerial.println(F("#TAICHI: SUCCESS OPEN CLAW!"));
#endif
is_claw_ok = true;
@ -1040,7 +1040,7 @@ bool OpenClawAndCheck(void)
#ifdef TAICHI_DEBUG
//调试输出失败信息
NeoSerial.println("#TAICHI: $$$$$$$$$$FAIL CLAW!$$$$$$$$$$");
NeoSerial.println(F("#TAICHI: $$$$$$$$$$FAIL CLAW!$$$$$$$$$$"));
#endif
is_claw_ok = false;

View File

@ -123,8 +123,8 @@ void Move::Forward(float speed_rate)
#ifdef MOVE_DEBUG
//调试输出前进状态
NeoSerial.print("#MOVE: Move Forward");
NeoSerial.print(" speed_rate: "); NeoSerial.println(speed_rate);
NeoSerial.print(F("#MOVE: Move Forward"));
NeoSerial.print(F(" speed_rate: ")); NeoSerial.println(speed_rate);
#endif
}
@ -143,8 +143,8 @@ void Move::Backward(float speed_rate)
#ifdef MOVE_DEBUG
//调试输出后退状态
NeoSerial.print("#MOVE: Move Backward");
NeoSerial.print(" speed_rate: "); NeoSerial.println(speed_rate);
NeoSerial.print(F("#MOVE: Move Backward"));
NeoSerial.print(F(" speed_rate: ")); NeoSerial.println(speed_rate);
#endif
}
@ -163,8 +163,8 @@ void Move::ForLeftward(float speed_rate, float turn_speed_rate)
#ifdef MOVE_DEBUG
//调试输出向前左转状态
NeoSerial.print("#MOVE: Move ForLeftward");
NeoSerial.print(" speed_rate: "); NeoSerial.print(speed_rate); NeoSerial.print(" turn_speed_rate: "); NeoSerial.println(turn_speed_rate);
NeoSerial.print(F("#MOVE: Move ForLeftward"));
NeoSerial.print(F(" speed_rate: ")); NeoSerial.print(speed_rate); NeoSerial.print(F(" turn_speed_rate: ")); NeoSerial.println(turn_speed_rate);
#endif
}
@ -183,8 +183,8 @@ void Move::ForRightward(float speed_rate, float turn_speed_rate)
#ifdef MOVE_DEBUG
//调试输出向前右转状态
NeoSerial.print("#MOVE: Move ForRightward");
NeoSerial.print(" speed_rate: "); NeoSerial.print(speed_rate); NeoSerial.print(" turn_speed_rate: "); NeoSerial.println(turn_speed_rate);
NeoSerial.print(F("#MOVE: Move ForRightward"));
NeoSerial.print(F(" speed_rate: ")); NeoSerial.print(speed_rate); NeoSerial.print(F(" turn_speed_rate: ")); NeoSerial.println(turn_speed_rate);
#endif
}
@ -203,8 +203,8 @@ void Move::BackLeftward(float speed_rate, float turn_speed_rate)
#ifdef MOVE_DEBUG
//调试输出向后左转状态
NeoSerial.print("#MOVE: Move BackLeftward");
NeoSerial.print(" speed_rate: "); NeoSerial.print(speed_rate); NeoSerial.print(" turn_speed_rate: "); NeoSerial.println(turn_speed_rate);
NeoSerial.print(F("#MOVE: Move BackLeftward"));
NeoSerial.print(F(" speed_rate: ")); NeoSerial.print(speed_rate); NeoSerial.print(F(" turn_speed_rate: ")); NeoSerial.println(turn_speed_rate);
#endif
}
@ -223,8 +223,8 @@ void Move::BackRightward(float speed_rate, float turn_speed_rate)
#ifdef MOVE_DEBUG
//调试输出向后右转状态
NeoSerial.print("#MOVE: Move BackRightward");
NeoSerial.print(" speed_rate: "); NeoSerial.print(speed_rate); NeoSerial.print(" turn_speed_rate: "); NeoSerial.println(turn_speed_rate);
NeoSerial.print(F("#MOVE: Move BackRightward"));
NeoSerial.print(F(" speed_rate: ")); NeoSerial.print(speed_rate); NeoSerial.print(F(" turn_speed_rate: ")); NeoSerial.println(turn_speed_rate);
#endif
}
@ -243,7 +243,7 @@ void Move::Stop(void)
#ifdef MOVE_DEBUG
//调试输出制动状态
NeoSerial.println("#MOVE: Move Stop");
NeoSerial.println(F("#MOVE: Move Stop"));
#endif
}

View File

@ -79,10 +79,10 @@ void Radio::Send(char* message, uint8_t send_type, uint8_t send_times)
}
#ifdef RADIO_DEBUG
NeoSerial.print("#RADIO: SEND: ");
NeoSerial.print(F("#RADIO: SEND: "));
full_message[FULL_MESSAGE_SIZE - 1] = '\0';
NeoSerial.print(full_message);
NeoSerial.print(" TIMES: ");
NeoSerial.print(F(" TIMES: "));
NeoSerial.println(send_times);
#endif
@ -179,7 +179,7 @@ bool Radio::Receive(uint8_t ch, uint8_t status)
is_end_record = true;
#ifdef RADIO_DEBUG
NeoSerial.print("#RADIO: RECEIVE: ");
NeoSerial.print(F("#RADIO: RECEIVE: "));
NeoSerial.println(message);
#endif
@ -188,7 +188,7 @@ bool Radio::Receive(uint8_t ch, uint8_t status)
else //位数校验失败
{
#ifdef RADIO_DEBUG
NeoSerial.println("#RADIO: RECEIVE CHECK FAIL!");
NeoSerial.println(F("#RADIO: RECEIVE CHECK FAIL!"));
#endif
}
}

View File

@ -277,7 +277,7 @@ Point* Route::AddPoint(Point* front_point, int8_t x, int8_t y, uint8_t type, Poi
void Route::InitBaseRoute(void)
{
//基本路径数组
int8_t base_route[][3] =
const static int8_t base_route [][3] PROGMEM =
{
{0, 0, NORMAL_POINT},
{0, 1, NORMAL_POINT},

View File

@ -86,13 +86,13 @@ void Sensor::FlashGraySensor(uint8_t gray_sensor_num)
//调试输出闪烁信息
switch (gray_sensor_num)
{
case GRAY_1: NeoSerial.println("#SENSOR: FLASH GRAY_1 NOW!"); break;
case GRAY_2: NeoSerial.println("#SENSOR: FLASH GRAY_2 NOW!"); break;
case GRAY_3: NeoSerial.println("#SENSOR: FLASH GRAY_3 NOW!"); break;
case GRAY_4: NeoSerial.println("#SENSOR: FLASH GRAY_4 NOW!"); break;
case GRAY_5: NeoSerial.println("#SENSOR: FLASH GRAY_5 NOW!"); break;
case GRAY_6: NeoSerial.println("#SENSOR: FLASH GRAY_6 NOW!"); break;
case GRAY_7: NeoSerial.println("#SENSOR: FLASH GRAY_7 NOW!");
case GRAY_1: NeoSerial.println(F("#SENSOR: FLASH GRAY_1 NOW!")); break;
case GRAY_2: NeoSerial.println(F("#SENSOR: FLASH GRAY_2 NOW!")); break;
case GRAY_3: NeoSerial.println(F("#SENSOR: FLASH GRAY_3 NOW!")); break;
case GRAY_4: NeoSerial.println(F("#SENSOR: FLASH GRAY_4 NOW!")); break;
case GRAY_5: NeoSerial.println(F("#SENSOR: FLASH GRAY_5 NOW!")); break;
case GRAY_6: NeoSerial.println(F("#SENSOR: FLASH GRAY_6 NOW!")); break;
case GRAY_7: NeoSerial.println(F("#SENSOR: FLASH GRAY_7 NOW!"));
}
#endif
@ -125,17 +125,17 @@ bool Sensor::IsWhite(uint8_t gray_sensor_num)
//调试输出灰度值
switch (gray_sensor_num)
{
case GRAY_1: NeoSerial.print("#SENSOR: GRAY_1 and gate_val: "); break;
case GRAY_2: NeoSerial.print("#SENSOR: GRAY_2 and gate_val: "); break;
case GRAY_3: NeoSerial.print("#SENSOR: GRAY_3 and gate_val: "); break;
case GRAY_4: NeoSerial.print("#SENSOR: GRAY_4 and gate_val: "); break;
case GRAY_5: NeoSerial.print("#SENSOR: GRAY_5 and gate_val: "); break;
case GRAY_6: NeoSerial.print("#SENSOR: GRAY_6 and gate_val: "); break;
case GRAY_7: NeoSerial.print("#SENSOR: GRAY_7 and gate_val: ");
case GRAY_1: NeoSerial.print(F("#SENSOR: GRAY_1 and gate_val: ")); break;
case GRAY_2: NeoSerial.print(F("#SENSOR: GRAY_2 and gate_val: ")); break;
case GRAY_3: NeoSerial.print(F("#SENSOR: GRAY_3 and gate_val: ")); break;
case GRAY_4: NeoSerial.print(F("#SENSOR: GRAY_4 and gate_val: ")); break;
case GRAY_5: NeoSerial.print(F("#SENSOR: GRAY_5 and gate_val: ")); break;
case GRAY_6: NeoSerial.print(F("#SENSOR: GRAY_6 and gate_val: ")); break;
case GRAY_7: NeoSerial.print(F("#SENSOR: GRAY_7 and gate_val: "));
}
NeoSerial.print(gray_val);
NeoSerial.print(" ");
NeoSerial.print(F(" "));
NeoSerial.println(gray_gate);
#endif
@ -170,24 +170,24 @@ float Sensor::GrayDeviationRate(uint8_t gray_sensor_num)
//调试输出灰度值
switch (gray_sensor_num)
{
case GRAY_1: NeoSerial.print("#SENSOR: GRAY_1 and gate_val: "); break;
case GRAY_2: NeoSerial.print("#SENSOR: GRAY_2 and gate_val: "); break;
case GRAY_3: NeoSerial.print("#SENSOR: GRAY_3 and gate_val: "); break;
case GRAY_4: NeoSerial.print("#SENSOR: GRAY_4 and gate_val: "); break;
case GRAY_5: NeoSerial.print("#SENSOR: GRAY_5 and gate_val: "); break;
case GRAY_6: NeoSerial.print("#SENSOR: GRAY_6 and gate_val: "); break;
case GRAY_7: NeoSerial.print("#SENSOR: GRAY_7 and gate_val: ");
case GRAY_1: NeoSerial.print(F("#SENSOR: GRAY_1 and gate_val: ")); break;
case GRAY_2: NeoSerial.print(F("#SENSOR: GRAY_2 and gate_val: ")); break;
case GRAY_3: NeoSerial.print(F("#SENSOR: GRAY_3 and gate_val: ")); break;
case GRAY_4: NeoSerial.print(F("#SENSOR: GRAY_4 and gate_val: ")); break;
case GRAY_5: NeoSerial.print(F("#SENSOR: GRAY_5 and gate_val: ")); break;
case GRAY_6: NeoSerial.print(F("#SENSOR: GRAY_6 and gate_val: ")); break;
case GRAY_7: NeoSerial.print(F("#SENSOR: GRAY_7 and gate_val: "));
}
NeoSerial.print(gray_val);
NeoSerial.print(" ");
NeoSerial.print(F(" "));
NeoSerial.print(gray_gate);
#endif
deviarion_rate = (float)gray_val / gray_gate;
#ifdef SENSOR_DEBUG
NeoSerial.print(" deviarion_rate: ");
NeoSerial.print(F(" deviarion_rate: "));
NeoSerial.println(deviarion_rate);
#endif
@ -210,12 +210,12 @@ bool Sensor::IsPushed(uint8_t button_num)
#ifdef SENSOR_DEBUG
//调试输出按钮状态
if (button_num == BUTTON_1)
NeoSerial.print("#SENSOR: BUTTON_1: ");
else NeoSerial.print("#SENSOR: BUTTON_2: ");
NeoSerial.print(F("#SENSOR: BUTTON_1: "));
else NeoSerial.print(F("#SENSOR: BUTTON_2: "));
if (button_val == LOW)
NeoSerial.println("pushed");
else NeoSerial.println("released");
NeoSerial.println(F("pushed"));
else NeoSerial.println(F("released"));
#endif
if (button_val == LOW)
@ -235,7 +235,7 @@ void Sensor::StartHMC5883(void)
#ifdef SENSOR_DEBUG
//调试输出
NeoSerial.println("#SENSOR: Start HMC5883");
NeoSerial.println(F("#SENSOR: Start HMC5883"));
#endif
}
@ -243,7 +243,7 @@ void Sensor::StartHMC5883(void)
//返回朝向角
float Sensor::GetAngle(void)
{
long x, y, z;
long x = 0, y = 0, z = 0;
Wire.beginTransmission(HMC5883_ADDRESS);
Wire.write(0x03);
@ -270,7 +270,7 @@ float Sensor::GetAngle(void)
#ifdef SENSOR_DEBUG
//调试输出朝向角
NeoSerial.print("#SENSOR: Angle Value: ");
NeoSerial.print(F("#SENSOR: Angle Value: "));
NeoSerial.println(angle);
#endif

View File

@ -45,9 +45,9 @@ void Servo::MoveServo(uint8_t servo_id, uint16_t position, uint16_t time)
#ifdef SERVO_DEBUG
//调试输出动作组执行信息
NeoSerial.print("#SERVO: MoveServo: "); NeoSerial.print((int)servo_id);
NeoSerial.print(" position: "); NeoSerial.print((int)position);
NeoSerial.print(" time: "); NeoSerial.println((int)time);
NeoSerial.print(F("#SERVO: MoveServo: ")); NeoSerial.print((int)servo_id);
NeoSerial.print(F(" position: ")); NeoSerial.print((int)position);
NeoSerial.print(F(" time: ")); NeoSerial.println((int)time);
#endif
}
@ -70,7 +70,7 @@ void Servo::RunActionGroup(uint8_t action_num, uint16_t times)
#ifdef SERVO_DEBUG
//调试输出动作组执行信息
NeoSerial.print("#SERVO: RunServoActionGroup: ");
NeoSerial.print(F("#SERVO: RunServoActionGroup: "));
NeoSerial.println((int)action_num);
#endif
}
@ -89,7 +89,7 @@ void Servo::StopActionGroup(void)
#ifdef SERVO_DEBUG
//调试输出动作组停止信息
NeoSerial.println("#SERVO: StopServoActionGroup");
NeoSerial.println(F("#SERVO: StopServoActionGroup"));
#endif
}
@ -112,9 +112,9 @@ void Servo::SetActionGroupSpeed(uint8_t action_num, float speed)
#ifdef SERVO_DEBUG
//调试输出动作组速度设定信息
NeoSerial.print("#SERVO: SetServoActionGroupSpeed: ");
NeoSerial.print(F("#SERVO: SetServoActionGroupSpeed: "));
NeoSerial.print((int)action_num);
NeoSerial.print(" Speed: ");
NeoSerial.print(F(" Speed: "));
NeoSerial.println(speed);
#endif
}