AP_Camera: keep trying to initialize RunCam after boot

This commit is contained in:
Andy Piper 2020-08-02 07:59:13 +01:00 committed by Andrew Tridgell
parent 2db57dffac
commit ab1d0d53f3
2 changed files with 20 additions and 22 deletions

View File

@ -103,7 +103,7 @@ AP_RunCam::Request::Length AP_RunCam::Request::_expected_responses_length[RUNCAM
// the protocol for Runcam Device definition
static const uint8_t RUNCAM_HEADER = 0xCC;
static const uint8_t RUNCAM_OSD_MENU_DEPTH = 2;
static const uint32_t RUNCAM_INIT_INTERVAL_MS = 500;
static const uint32_t RUNCAM_INIT_INTERVAL_MS = 1000;
static const uint32_t RUNCAM_OSD_UPDATE_INTERVAL_MS = 100; // 10Hz
// menu structures of runcam devices
@ -156,7 +156,7 @@ void AP_RunCam::init()
_in_menu = -1;
}
uart->begin(115200);
start_uart();
// first transition is from initialized to ready
_transition_start_ms = AP_HAL::millis();
@ -762,11 +762,24 @@ void AP_RunCam::drain()
uart->discard_input();
}
// start the uart if we have one
void AP_RunCam::start_uart()
{
// 8N1 communication
uart->configure_parity(0);
uart->set_stop_bits(1);
uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
uart->set_blocking_writes(false); // updates run in the main thread
uart->set_options(uart->get_options() | AP_HAL::UARTDriver::OPTION_NODMA_TX | AP_HAL::UARTDriver::OPTION_NODMA_RX);
uart->begin(115200, 10, 10);
uart->discard_input();
}
// get the device info (firmware version, protocol version and features)
void AP_RunCam::get_device_info()
{
send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, 0, RUNCAM_INIT_INTERVAL_MS,
_boot_delay_ms / RUNCAM_INIT_INTERVAL_MS, FUNCTOR_BIND_MEMBER(&AP_RunCam::parse_device_info, void, const Request&));
send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, 0, RUNCAM_INIT_INTERVAL_MS * 4,
-1, FUNCTOR_BIND_MEMBER(&AP_RunCam::parse_device_info, void, const Request&));
}
// map a Event to a SimulationOperation
@ -911,22 +924,6 @@ void AP_RunCam::send_packet(Command command, uint8_t param)
uart->flush();
}
uint8_t AP_RunCam::crc8_high_first(uint8_t *ptr, uint8_t len)
{
uint8_t crc = 0x00;
while (len--) {
crc ^= *ptr++;
for (uint8_t i = 8; i > 0; --i) {
if (crc & 0x80) {
crc = (crc << 1) ^ 0x31;
} else {
crc = (crc << 1);
}
}
}
return (crc);
}
// handle a device info response
void AP_RunCam::parse_device_info(const Request& request)
{
@ -987,6 +984,7 @@ bool AP_RunCam::request_pending(uint32_t now)
if (_pending_request._max_retry_times > 0) {
// request timed out, so resend
debug("retrying[%d] command 0x%X, op 0x%X\n", int(_pending_request._max_retry_times), int(_pending_request._command), int(_pending_request._param));
start_uart();
_pending_request._device->send_packet(_pending_request._command, _pending_request._param);
_pending_request._recv_response_length = 0;
_pending_request._request_timestamp_ms = now;

View File

@ -379,6 +379,8 @@ private:
void receive();
// empty the receive side of the serial port
void drain();
// start the uart with appropriate settings
void start_uart();
// get the RunCam device information
void get_device_info();
@ -399,8 +401,6 @@ private:
uint16_t maxRetryTimes, parse_func_t parseFunc);
// send a packet to the serial port
void send_packet(Command command, uint8_t param);
// crc functions
static uint8_t crc8_high_first(uint8_t *ptr, uint8_t len);
// handle a device info response
void parse_device_info(const Request& request);
// wait for the RunCam device to be fully ready