串口现在使用 NeoHWSerial 库

This commit is contained in:
lxbpxylps@126.com 2021-03-21 23:31:43 +08:00
parent a5c25cbc80
commit 2cfc9a62fc
4 changed files with 88 additions and 74 deletions

View File

@ -1,5 +1,9 @@
#include <Arduino.h>
#ifdef SENSOR_DEBUG
#include <NeoHWSerial.h>
#endif
#include "moveTaiChi.h"
@ -119,8 +123,8 @@ void Move::Forward(float speed_rate)
#ifdef MOVE_DEBUG
//调试输出前进状态
Serial.print("#MOVE: Move Forward");
Serial.print(" speed_rate: "); Serial.println(speed_rate);
NeoSerial.print("#MOVE: Move Forward");
NeoSerial.print(" speed_rate: "); NeoSerial.println(speed_rate);
#endif
}
@ -139,8 +143,8 @@ void Move::Backward(float speed_rate)
#ifdef MOVE_DEBUG
//调试输出后退状态
Serial.print("#MOVE: Move Backward");
Serial.print(" speed_rate: "); Serial.println(speed_rate);
NeoSerial.print("#MOVE: Move Backward");
NeoSerial.print(" speed_rate: "); NeoSerial.println(speed_rate);
#endif
}
@ -159,8 +163,8 @@ void Move::ForLeftward(float speed_rate, float turn_speed_rate)
#ifdef MOVE_DEBUG
//调试输出向前左转状态
Serial.print("#MOVE: Move ForLeftward");
Serial.print(" speed_rate: "); Serial.print(speed_rate); Serial.print(" turn_speed_rate: "); Serial.println(turn_speed_rate);
NeoSerial.print("#MOVE: Move ForLeftward");
NeoSerial.print(" speed_rate: "); NeoSerial.print(speed_rate); NeoSerial.print(" turn_speed_rate: "); NeoSerial.println(turn_speed_rate);
#endif
}
@ -179,8 +183,8 @@ void Move::ForRightward(float speed_rate, float turn_speed_rate)
#ifdef MOVE_DEBUG
//调试输出向前右转状态
Serial.print("#MOVE: Move ForRightward");
Serial.print(" speed_rate: "); Serial.print(speed_rate); Serial.print(" turn_speed_rate: "); Serial.println(turn_speed_rate);
NeoSerial.print("#MOVE: Move ForRightward");
NeoSerial.print(" speed_rate: "); NeoSerial.print(speed_rate); NeoSerial.print(" turn_speed_rate: "); NeoSerial.println(turn_speed_rate);
#endif
}
@ -199,8 +203,8 @@ void Move::BackLeftward(float speed_rate, float turn_speed_rate)
#ifdef MOVE_DEBUG
//调试输出向后左转状态
Serial.print("#MOVE: Move BackLeftward");
Serial.print(" speed_rate: "); Serial.print(speed_rate); Serial.print(" turn_speed_rate: "); Serial.println(turn_speed_rate);
NeoSerial.print("#MOVE: Move BackLeftward");
NeoSerial.print(" speed_rate: "); NeoSerial.print(speed_rate); NeoSerial.print(" turn_speed_rate: "); NeoSerial.println(turn_speed_rate);
#endif
}
@ -219,8 +223,8 @@ void Move::BackRightward(float speed_rate, float turn_speed_rate)
#ifdef MOVE_DEBUG
//调试输出向后右转状态
Serial.print("#MOVE: Move BackRightward");
Serial.print(" speed_rate: "); Serial.print(speed_rate); Serial.print(" turn_speed_rate: "); Serial.println(turn_speed_rate);
NeoSerial.print("#MOVE: Move BackRightward");
NeoSerial.print(" speed_rate: "); NeoSerial.print(speed_rate); NeoSerial.print(" turn_speed_rate: "); NeoSerial.println(turn_speed_rate);
#endif
}
@ -239,7 +243,7 @@ void Move::Stop(void)
#ifdef MOVE_DEBUG
//调试输出制动状态
Serial.println("#MOVE: Move Stop");
NeoSerial.println("#MOVE: Move Stop");
#endif
}

View File

@ -1,6 +1,10 @@
#include <Arduino.h>
#include <Wire.h>
#ifdef SENSOR_DEBUG
#include <NeoHWSerial.h>
#endif
#include "sensorTaiChi.h"
@ -81,13 +85,13 @@ void Sensor::FlashGraySensor(uint8_t gray_sensor_num)
//调试输出闪烁信息
switch (gray_sensor_num)
{
case GRAY_1: Serial.println("#SENSOR: FLASH GRAY_1 NOW!"); break;
case GRAY_2: Serial.println("#SENSOR: FLASH GRAY_2 NOW!"); break;
case GRAY_3: Serial.println("#SENSOR: FLASH GRAY_3 NOW!"); break;
case GRAY_4: Serial.println("#SENSOR: FLASH GRAY_4 NOW!"); break;
case GRAY_5: Serial.println("#SENSOR: FLASH GRAY_5 NOW!"); break;
case GRAY_6: Serial.println("#SENSOR: FLASH GRAY_6 NOW!"); break;
case GRAY_7: Serial.println("#SENSOR: FLASH GRAY_7 NOW!");
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!");
}
#endif
@ -120,18 +124,18 @@ bool Sensor::IsWhite(uint8_t gray_sensor_num)
//调试输出灰度值
switch (gray_sensor_num)
{
case GRAY_1: Serial.print("#SENSOR: GRAY_1 and gate_val: "); break;
case GRAY_2: Serial.print("#SENSOR: GRAY_2 and gate_val: "); break;
case GRAY_3: Serial.print("#SENSOR: GRAY_3 and gate_val: "); break;
case GRAY_4: Serial.print("#SENSOR: GRAY_4 and gate_val: "); break;
case GRAY_5: Serial.print("#SENSOR: GRAY_5 and gate_val: "); break;
case GRAY_6: Serial.print("#SENSOR: GRAY_6 and gate_val: "); break;
case GRAY_7: Serial.print("#SENSOR: GRAY_7 and gate_val: ");
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: ");
}
Serial.print(gray_val);
Serial.print(" ");
Serial.println(gray_gate);
NeoSerial.print(gray_val);
NeoSerial.print(" ");
NeoSerial.println(gray_gate);
#endif
if (gray_val > gray_gate)
@ -165,25 +169,25 @@ float Sensor::GrayDeviationRate(uint8_t gray_sensor_num)
//调试输出灰度值
switch (gray_sensor_num)
{
case GRAY_1: Serial.print("#SENSOR: GRAY_1 and gate_val: "); break;
case GRAY_2: Serial.print("#SENSOR: GRAY_2 and gate_val: "); break;
case GRAY_3: Serial.print("#SENSOR: GRAY_3 and gate_val: "); break;
case GRAY_4: Serial.print("#SENSOR: GRAY_4 and gate_val: "); break;
case GRAY_5: Serial.print("#SENSOR: GRAY_5 and gate_val: "); break;
case GRAY_6: Serial.print("#SENSOR: GRAY_6 and gate_val: "); break;
case GRAY_7: Serial.print("#SENSOR: GRAY_7 and gate_val: ");
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: ");
}
Serial.print(gray_val);
Serial.print(" ");
Serial.print(gray_gate);
NeoSerial.print(gray_val);
NeoSerial.print(" ");
NeoSerial.print(gray_gate);
#endif
deviarion_rate = (float)gray_val / gray_gate;
#ifdef SENSOR_DEBUG
Serial.print(" deviarion_rate: ");
Serial.println(deviarion_rate);
NeoSerial.print(" deviarion_rate: ");
NeoSerial.println(deviarion_rate);
#endif
return deviarion_rate;
@ -205,12 +209,12 @@ bool Sensor::IsPushed(uint8_t button_num)
#ifdef SENSOR_DEBUG
//调试输出按钮状态
if (button_num == BUTTON_1)
Serial.print("#SENSOR: BUTTON_1: ");
else Serial.print("#SENSOR: BUTTON_2: ");
NeoSerial.print("#SENSOR: BUTTON_1: ");
else NeoSerial.print("#SENSOR: BUTTON_2: ");
if (button_val == LOW)
Serial.println("pushed");
else Serial.println("released");
NeoSerial.println("pushed");
else NeoSerial.println("released");
#endif
if (button_val == LOW)
@ -227,6 +231,11 @@ void Sensor::StartHMC5883(void)
Wire.write(0x02);
Wire.write(0x00);
Wire.endTransmission();
#ifdef SENSOR_DEBUG
//调试输出
NeoSerial.println("#SENSOR: Start HMC5883");
#endif
}
@ -260,8 +269,8 @@ float Sensor::GetAngle(void)
#ifdef SENSOR_DEBUG
//调试输出朝向角
Serial.print("#SENSOR: Angle Value: ");
Serial.println(angle);
NeoSerial.print("#SENSOR: Angle Value: ");
NeoSerial.println(angle);
#endif
return angle;

View File

@ -1,3 +1,5 @@
#include <NeoHWSerial.h>
#include "servoTaiChi.h"
@ -11,16 +13,14 @@
Servo::Servo()
{
SerialX = &DEFAULT_SERVO_SERIAL_NUM; //默认使用 Mega 板 18 19 作为串口通信端口
SerialX->begin(SERVO_BAUD_RATE);
NeoSerialX = &SERVO_SERIAL_NUM; //默认使用 Mega 板 18 19 作为串口通信端口
}
//指定串口通信端
Servo::Servo(HardwareSerial& serial_num)
//打开串
void Servo::BeginTransmit(unsigned long baud_rate)
{
SerialX = &serial_num;
SerialX->begin(SERVO_BAUD_RATE);
NeoSerialX->begin(SERVO_BAUD_RATE);
}
@ -40,13 +40,13 @@ void Servo::MoveServo(uint8_t servo_id, uint16_t position, uint16_t time)
buf[8] = GET_LOW_BYTE(position); //填充目标位置的低八位
buf[9] = GET_HIGH_BYTE(position); //填充目标位置的高八位
SerialX->write(buf, 10);
NeoSerialX->write(buf, 10);
#ifdef SERVO_DEBUG
//调试输出动作组执行信息
Serial.print("#SERVO: MoveServo: "); Serial.print((int)servo_id);
Serial.print(" position: "); Serial.print((int)position);
Serial.print(" time: "); Serial.println((int)time);
NeoSerial.print("#SERVO: MoveServo: "); NeoSerial.print((int)servo_id);
NeoSerial.print(" position: "); NeoSerial.print((int)position);
NeoSerial.print(" time: "); NeoSerial.println((int)time);
#endif
}
@ -65,12 +65,12 @@ void Servo::RunActionGroup(uint8_t action_num, uint16_t times)
buf[5] = GET_LOW_BYTE(times); //取得要运行次数的低八位
buf[6] = GET_HIGH_BYTE(times); //取得要运行次数的高八位
SerialX->write(buf, 7); //发送数据帧
NeoSerialX->write(buf, 7); //发送数据帧
#ifdef SERVO_DEBUG
//调试输出动作组执行信息
Serial.print("#SERVO: RunServoActionGroup: ");
Serial.println((int)action_num);
NeoSerial.print("#SERVO: RunServoActionGroup: ");
NeoSerial.println((int)action_num);
#endif
}
@ -84,11 +84,11 @@ void Servo::StopActionGroup(void)
buf[2] = 2; //数据长度数据帧除帧头部分数据字节数此命令固定为2
buf[3] = CMD_ACTION_GROUP_STOP; //填充停止运行动作组命令
SerialX->write(buf, 4); //发送数据帧
NeoSerialX->write(buf, 4); //发送数据帧
#ifdef SERVO_DEBUG
//调试输出动作组停止信息
Serial.println("#SERVO: StopServoActionGroup");
NeoSerial.println("#SERVO: StopServoActionGroup");
#endif
}
@ -107,14 +107,14 @@ void Servo::SetActionGroupSpeed(uint8_t action_num, float speed)
buf[5] = GET_LOW_BYTE(speed_int); //获得目标速度的低八位
buf[6] = GET_HIGH_BYTE(speed_int); //获得目标熟读的高八位
SerialX->write(buf, 7); //发送数据帧
NeoSerialX->write(buf, 7); //发送数据帧
#ifdef SERVO_DEBUG
//调试输出动作组速度设定信息
Serial.print("#SERVO: SetServoActionGroupSpeed: ");
Serial.print((int)action_num);
Serial.print(" Speed: ");
Serial.println(speed);
NeoSerial.print("#SERVO: SetServoActionGroupSpeed: ");
NeoSerial.print((int)action_num);
NeoSerial.print(" Speed: ");
NeoSerial.println(speed);
#endif
}
@ -142,7 +142,7 @@ void Servo::Reset(float speed)
}
//放下爪子,指定速度
//放下爪子,指定速度
void Servo::Down(float speed)
{
SetActionGroupSpeed(ACTION_DOWN_NUM, speed);

View File

@ -9,9 +9,9 @@
#define SERVO_DEBUG
//默认与舵机控制板连接串口
//默认使用 Mega 板 18 19 作为串口通信端口
#define DEFAULT_SERVO_SERIAL_NUM Serial1
//与舵机控制板连接串口
//使用 Mega 板 18 19 作为串口通信端口
#define SERVO_SERIAL_NUM NeoSerial1
//与舵机控制板串口通信波特率
@ -52,7 +52,8 @@ class Servo
{
public:
Servo();
Servo(HardwareSerial &serial_num); //构造函数,指定串口通信端口
void BeginTransmit(unsigned long baud_rate = SERVO_BAUD_RATE); //打开串口
void MoveServo(uint8_t servo_id, uint16_t position, uint16_t time); //控制单个舵机转动
@ -73,7 +74,7 @@ public:
void StopAndReset(float speed = SERVO_NORMAL_SPEED); //停止舵机并恢复初始状态,指定速度
private:
HardwareSerial *SerialX;
NeoHWSerial* NeoSerialX;
};