Browse Source

增加串口发送测试,半成品

celiu-4.0.17-rc8
zbr 4 years ago
parent
commit
6a2adf6a45
  1. 2
      ArduCopter/Copter.h
  2. 3
      ArduCopter/Parameters.cpp
  3. 2
      ArduCopter/Parameters.h
  4. 22
      ArduCopter/UserCode.cpp
  5. 106
      ArduCopter/zr_flight.cpp
  6. 2
      copy.sh
  7. 6
      libraries/AP_SerialManager/AP_SerialManager.cpp
  8. 3
      libraries/AP_SerialManager/AP_SerialManager.h

2
ArduCopter/Copter.h

@ -1039,6 +1039,8 @@ public: @@ -1039,6 +1039,8 @@ public:
void zr_SlowLoop();
bool flow_start_sw;
bool flow_index_sw;
void control_serial_test();
uint8_t serial_send_step;
};
extern Copter copter;

3
ArduCopter/Parameters.cpp

@ -151,6 +151,9 @@ const AP_Param::Info Copter::var_info[] = { @@ -151,6 +151,9 @@ const AP_Param::Info Copter::var_info[] = {
// @User: Standard
GSCALAR(zr_rtl_delay, "ZR_RTL_DELAY", ZR_RTL_DELAY),
GSCALAR(zr_send_type, "ZR_SERIAL_TP", 0),
#if MODE_RTL_ENABLED == ENABLED
// @Param: RTL_ALT
// @DisplayName: RTL Altitude

2
ArduCopter/Parameters.h

@ -389,6 +389,7 @@ public: @@ -389,6 +389,7 @@ public:
k_param_zr_tk_req_alt,
k_param_zr_tk_delay,
k_param_zr_rtl_delay,
k_param_zr_send_type,
// the k_param_* space is 9-bits in size
// 511: reserved
};
@ -500,6 +501,7 @@ public: @@ -500,6 +501,7 @@ public:
AP_Int32 zr_tk_req_alt;
AP_Int16 zr_tk_delay;
AP_Int16 zr_rtl_delay;
AP_Int8 zr_send_type;
// Note: keep initializers here in the same order as they are declared
// above.
Parameters()

22
ArduCopter/UserCode.cpp

@ -59,6 +59,9 @@ void Copter::userhook_SuperSlowLoop() @@ -59,6 +59,9 @@ void Copter::userhook_SuperSlowLoop()
int32_t real_alt = gps.location().alt + gps.get_gps_delt_alt();
flow_measure.flow_auto_measure(flow_start_sw,flow_index_sw, real_alt, measure_time);
if(serial_send_step!=0)
control_serial_test();
}
#endif
@ -87,6 +90,7 @@ void Copter::userhook_auxSwitch1(uint8_t ch_flag) @@ -87,6 +90,7 @@ void Copter::userhook_auxSwitch1(uint8_t ch_flag)
void Copter::userhook_auxSwitch2(uint8_t ch_flag)
{
// put your aux switch #2 handler here (CHx_OPT = 48)
switch (ch_flag) {
case 2: {
// relay.on(2);
@ -101,10 +105,28 @@ void Copter::userhook_auxSwitch2(uint8_t ch_flag) @@ -101,10 +105,28 @@ void Copter::userhook_auxSwitch2(uint8_t ch_flag)
break;
}
}
}
void Copter::userhook_auxSwitch3(uint8_t ch_flag)
{
// put your aux switch #3 handler here (CHx_OPT = 49)
switch (ch_flag) {
case 2: {
serial_send_step = 2;
gcs().send_text(MAV_SEVERITY_NOTICE, "[NOTE]seials s108!");
break;
}
case 1: {
serial_send_step = 1;
gcs().send_text(MAV_SEVERITY_NOTICE, "[NOTE]serial +++!");
break;
}
case 0: {
serial_send_step = 0;
gcs().send_text(MAV_SEVERITY_NOTICE, "[NOTE]serial: off!");
break;
}
}
}
#endif

106
ArduCopter/zr_flight.cpp

@ -102,4 +102,110 @@ void Copter::zr_SuperSlowLoop(){ @@ -102,4 +102,110 @@ void Copter::zr_SuperSlowLoop(){
// flow_measure.flow_auto_measure(flow_start_sw,flow_index_sw, real_alt, measure_time);
}
void Copter::control_serial_test()
{
uint8_t select_power = g.zr_send_type;
if(select_power == 0)
return;
const uint8_t start_cmd[] = "ATS108?\n";
const uint8_t power_100mw[] = "ATS108=20\n";
const uint8_t power_200mw[] = "ATS108=23\n";
const uint8_t power_320mw[] = "ATS108=25\n";
const uint8_t power_500mw[] = "ATS108=27\n";
const uint8_t power_1w[] = "ATS108=30\n";
const uint8_t write_cmd[] = "AT&W\n";
uint8_t power_s[] = " ";
uint8_t read_s[50] = "";
static uint8_t last_step;
switch (select_power)
{
case 1:
memcpy(power_s,power_100mw,11);
break;
case 2:
memcpy(power_s,power_200mw,11);
break;
case 3:
memcpy(power_s,power_320mw,11);
break;
case 4:
memcpy(power_s,power_500mw,11);
break;
case 5:
memcpy(power_s,power_1w,11);
break;
default:
break;
}
// const uint8_t power_select[] = power_s;
AP_HAL::UARTDriver *_uart;
uint32_t nbytes;
static uint8_t read_len;
_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Serial_Set,0);
if (_uart == nullptr) {
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: control_serial_test serial not set");
return;
}
nbytes = _uart->available();
while(nbytes-->0)
{
uint8_t temp = _uart->read();
read_s[read_len] = temp;
read_len++;
// gcs().send_text(MAV_SEVERITY_INFO,"%c",temp);
}
if(read_len > 49){
read_len = 0;
gcs().send_text(MAV_SEVERITY_INFO,"read:%s",read_s);
}
if(read_len > 0){
static uint8_t cnt = 0;
cnt++;
if(cnt > 10)
{
read_len = 0;
gcs().send_text(MAV_SEVERITY_INFO,"read cnt:%s",read_s);
cnt = 0;
}
}
uint8_t prt[] = "get new serial data";
if(last_step != serial_send_step ){
switch (serial_send_step)
{
gcs().send_text(MAV_SEVERITY_INFO,"serial:%s",prt);
case 0:
/* code */
break;
case 1:
if (_uart->txspace() > sizeof(start_cmd)) {
_uart->write(start_cmd, sizeof(start_cmd));
}
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: start_cmd");
break;
case 2:
if (_uart->txspace() > sizeof(power_s)) {
_uart->write(power_s, sizeof(power_s));
}
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: power_s:%d",select_power);
if (_uart->txspace() > sizeof(write_cmd)) {
_uart->write(write_cmd, sizeof(write_cmd));
}
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE:----- set ok");
break;
default:
break;
}
last_step = serial_send_step;
}
}
#endif

2
copy.sh

@ -1,2 +1,2 @@ @@ -1,2 +1,2 @@
sudo cp ./build/Pixhawk4/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/zr-flow-v2-rc2.px4
sudo cp ./build/Pixhawk4/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/zr-v4/wsl/zr-flow-v2-test.px4

6
libraries/AP_SerialManager/AP_SerialManager.cpp

@ -480,6 +480,12 @@ void AP_SerialManager::init() @@ -480,6 +480,12 @@ void AP_SerialManager::init()
AP_SERIALMANAGER_FLOW_MEASURE_BUFSIZE_RX,
AP_SERIALMANAGER_FLOW_MEASURE_BUFSIZE_TX);
break;
case SerialProtocol_Serial_Set: // add by @Brown
state[i].uart->begin(map_baudrate(state[i].baud),
AP_SERIALMANAGER_FLOW_MEASURE_BUFSIZE_RX,
AP_SERIALMANAGER_FLOW_MEASURE_BUFSIZE_TX);
break;
#ifndef HAL_BUILD_AP_PERIPH

3
libraries/AP_SerialManager/AP_SerialManager.h

@ -129,7 +129,8 @@ public: @@ -129,7 +129,8 @@ public:
SerialProtocol_RCIN = 23,
SerialProtocol_Battery =24,
SerialProtocol_Camera_X30T = 25,
SerialProtocol_Flow_Measure = 26 // add by @Brown
SerialProtocol_Flow_Measure = 26, // add by @Brown
SerialProtocol_Serial_Set = 27 // add by @Brown
};
// get singleton instance

Loading…
Cancel
Save