1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-12 19:10:27 +03:00

CJMCU removed

This commit is contained in:
Pawel Spychalski (DzikuVx) 2018-04-24 08:48:39 +02:00
parent a9902a37cd
commit 5420d5374d
10 changed files with 2 additions and 404 deletions

View file

@ -30,7 +30,6 @@ doc_files=(
'Boards.md'
'Board - AlienFlight.md'
'Board - ChebuzzF3.md'
'Board - CJMCU.md'
'Board - ColibriRace.md'
'Board - Motolab.md'
'Board - Paris Air Hero 32.md'

View file

@ -1,144 +0,0 @@
# Board - CJMCU
The CJMCU is a tiny (80mm) board running a STM32F103, which contains a 3-Axis Compass (HMC5883L)
and an Accelerometer/Gyro (MPU6050).
This board does not have an onboard USB-Serial converter, so an external adapter is needed.
# Hardware revisions
| Revision | Notes |
| -------- | ----- |
| 1 | No boot jumper pads by LED1. Uses blue and red LEDs |
| 2 | Boot jumper pads presoldered with pins and a jumper by LED1. Uses green and red LEDs. |
Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlier versions to version 2 boards.
# Pins
## RX Connections
| Pin Label | Description |
| --------- | ------------------------ |
| PA0 | RC Channel 1 |
| PA1 | RC Channel 2 |
| PA2 | RC Channel 3 / USART2 TX |
| PA3 | RC Channel 4 / USART2 RX |
| VCC | Power (See note) |
| GND | Ground |
NOTE: The VCC RX Pin is not regulated and will supply what ever voltage is provided to the board, this will mean it'll provide 5v if a 5v serial connection is used. Be careful if you are using a voltage sensitive RX. A regulated 3.3v supply can be found on the top pin of column 1, just below the RX GND pin.
## Serial Connections
USART1 (along with power) is on the following pins.
| Pin Label | Description |
| --------- | --------------- |
| TX1 | UART1 TX |
| RX1 | UART2 RX |
| GND | Ground |
| 3V3 | Power +3.3v |
| 5V | Power +5v |
USART2 is the following pins.
| Pin Label | Description |
| --------- | ----------- |
| PA2 | USART2 TX |
| PA3 | USART2 RX |
## Power Connections
| Pin Label | Description |
| --------- | ----------------------- |
| Power + | Power - 1 Cell 3.7v Max |
| Power - | Ground |
## Motor Connections
In standard QUADX configuration, the motors are mapped:
| INAV | CJMCU |
| ----------- | ------ |
| Motor 1 | Motor3 |
| Motor 2 | Motor2 |
| Motor 3 | Motor4 |
| Motor 4 | Motor1 |
It is therefore simplest to wire the motors:
* Motor 1 -> Clockwise
* Motor 2 -> Anti-Clockwise
* Motor 3 -> Clockwise
* Motor 4 -> Anti-Clockwise
If you are using the Hubsan x4/Ladybird motors, clockwise are Blue (GND) / Red (VCC) wires, anticlockwise
are Black (GND) / White (VCC).
i.e. there is one wire on each motor out of the standard RED/BLACK VCC/GND polarity colors that can be used to identify polarity.
If you have wired as above, Motor1/Motor2 on the board will be forward.
# Connecting a Serial-USB Adapter
You will need a USB -> Serial UART adapter. Connect:
| Adapter | CJMCU |
| ----------------- | -------------------------- |
| Either 3.3v OR 5v | The correct 3.3v OR 5v pin |
| RX | TX |
| TX | RX |
When first connected this should power up the board, and will be in bootloader mode. If this does not happen, check
the charge switch is set to POW.
After the flashing process has been completed, this will allow access via the INAV configurator to change
settings or flash a new firmware.
WARNING: If the motors are connected and the board boots into the bootloader, they will start
to spin after around 20 seconds, it is recommended not to connect the motors until the board
is flashed.
# Flashing
To flash the board:
* Open INAV Configurator
* Choose the latest CJMCU firmware from the list.
* Select "Load Firmware [Online]" and wait for the firmware to download.
* Tick "No Reboot Sequence" and "Full Chip Erase"
* Connect the USB->Serial adapter to the board
* Select the USB-UART adapter from the top left box
* Click "Flash Firmware"
* You should see "Programming: SUCCESSFUL" in the log box
* Click "Connect" -> This should open the "Initial Setup" tab and you should see sensor data from the quad shown
* Unplug the quad and short the 2 "BOOT0" pins. Revision 1 boards require this to be soldered, revision 2 boards can connect the included jumper to the two pre-soldered pins - This prevents the board from going into bootloader mode on next
boot, if anything goes wrong, simply disconnect these two pins and the bootloader will start, allowing you to reflash. You cannot
overwrite the bootloader.
# Charging
The CJMCU has on it a TP4056 Lithium battery charging IC that can charge a 1S battery at 1A using a provided 5v supply attached to the 5v serial pin.
To charge an attached battery:
* Set the power switch to OFF
* Set the charge switch to CHG
* Plug in a 1S battery to the battery pins
* Plug in a 5v supply to the 5v serial pins
The charger will finish when either the battery reaches 4.2v, or the battery's voltage is greater than the charger's input voltage.
The two nearby LEDs will show the status of charging:
| Status | Green LED | Red LED |
|--------------------|-----------|-----------|
| Charging | On | Off |
| Finished | Off | On |
| 5v not connected | Off | Off |
| Batt not connected | Flashing | On |
# Helpful Hints
* If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500
for one of the the AUX channels which will result in it being always on
* Enabling the feature MOTOR_STOP helps with crashes so it doesn't try to keep spinning on its back
* When the power runs low, the quad will start jumping around a bit, if the flight behaviour seems strange, check your batteries charge

View file

@ -24,7 +24,7 @@ The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during bu
## Function
The bind code will actually work for CJMCU, EUSTM32F103RC, SPARKY targets (USART2). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
The bind code will actually work for EUSTM32F103RC, SPARKY targets (USART2). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
If the hardware bind plug is configured the bind mode will only be activated if the plug is set during the firmware start-up. The value of the spektrum_sat_bind parameter will be permanently preserved. The bind plug should be always removed for normal flying.
@ -46,7 +46,7 @@ http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
### Supported Hardware
CJMCU, SPARKY, EUSTM32F103RC and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug
SPARKY, EUSTM32F103RC and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug
### Connecting a Spektrum-compatible satellite to a Flip32+ flight controller

View file

@ -3,7 +3,6 @@
targets=("PUBLISHMETA=True" \
"RUNTESTS=True" \
"TARGET=CHEBUZZF3" \
"TARGET=CJMCU" \
"TARGET=COLIBRI_RACE" \
"TARGET=EUSTM32F103RC" \
"TARGET=SPRACINGF3" \

View file

@ -683,10 +683,6 @@ void init(void)
if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
batteryInit();
#ifdef CJMCU
LED2_ON;
#endif
#ifdef USE_PMW_SERVO_DRIVER
if (feature(FEATURE_PWM_SERVO_DRIVER)) {
pwmDriverInitialize();

View file

@ -1,47 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "drivers/sensor.h"
#include "drivers/exti.h"
#include "hardware_revision.h"
uint8_t hardwareRevision = UNKNOWN;
void detectHardwareRevision(void)
{
if (GPIOC->IDR & GPIO_Pin_15) {
hardwareRevision = REV_2;
} else {
hardwareRevision = REV_1;
}
}
void updateHardwareRevision(void)
{
}
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
{
return NULL;
}

View file

@ -1,31 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef enum cjmcuHardwareRevision_t {
UNKNOWN = 0,
REV_1, // Blue LED3
REV_2 // Green LED3
} cjmcuHardwareRevision_e;
extern uint8_t hardwareRevision;
void updateHardwareRevision(void);
void detectHardwareRevision(void);
struct extiConfig_s;
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);

View file

@ -1,45 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM4 - RC4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_IPD, TIM_USE_PWM }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11),TIM_Channel_4, 1, IOCFG_IPD, TIM_USE_PWM }, // PWM10 - OUT2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR }, // PWM7 - RC7
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR }, // PWM14 - OUT6
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR }, // PWM8 - RC8
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR }, // PWM13 - OUT5
/*
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_IPD }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_IPD }, // PWM6 - RC6
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 0, IOCFG_IPD }, // PWM12 - OUT4
*/
};

View file

@ -1,118 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
#define LED0 PC14
#define LED1 PC13
#define LED2 PC15
#undef BEEPER
#define USE_GYRO
#define USE_GYRO_MPU6050
#define USE_ACC
#define USE_ACC_MPU6050
//#define USE_MAG
//#define USE_MAG_HMC5883
#define USE_UART1
#define USE_UART2
#define SERIAL_PORT_COUNT 2
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1)
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_RX_NRF24
#ifdef USE_RX_NRF24
#define USE_RX_SPI
#define RX_SPI_INSTANCE SPI1
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
#define RX_IRQ_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
#define RX_CE_PIN PA4
#define RX_NSS_PIN PA11
#define RX_SCK_PIN PA5
#define RX_MISO_PIN PA6
#define RX_MOSI_PIN PA7
#define RX_IRQ_PIN PA8
// CJMCU has NSS on PA11, rather than the standard PA4
#define SPI1_NSS_PIN RX_NSS_PIN
#define SPI1_SCK_PIN RX_SCK_PIN
#define SPI1_MISO_PIN RX_MISO_PIN
#define SPI1_MOSI_PIN RX_MOSI_PIN
#define USE_RX_NRF24
//#define USE_RX_CX10
#define USE_RX_H8_3D
//#define USE_RX_INAV
//#define USE_RX_SYMA
//#define USE_RX_V202
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_SYMA_X5
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_INAV
#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_H8_3D
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_CX10A
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_V202_1M
#define DEFAULT_RX_TYPE RX_TYPE_SPI
//#define USE_TELEMETRY
//#define USE_TELEMETRY_LTM
//#define TELEMETRY_NRF24_LTM
#undef USE_RX_PWM
#undef USE_RX_PPM
#undef USE_SERIAL_RX
#undef SKIP_TASK_STATISTICS
#else
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define USE_RX_MSP
#define USE_SPEKTRUM_BIND
#define BIND_PIN PA3 // UART2, PA3
#endif //USE_RX_NRF24
#define BRUSHED_MOTORS
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_MOTOR_STOP)
#undef USE_SERIAL_PASSTHROUGH
// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
#define USE_QUAD_MIXER_ONLY
#undef USE_SERVOS
// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 4
// IO - assuming all IOs on 48pin package TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View file

@ -1,11 +0,0 @@
F1_TARGETS += $(TARGET)
FLASH_SIZE = 64
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6050.c \
drivers/compass/compass_hmc5883l.c \
hardware_revision.c \
telemetry/telemetry.c \
telemetry/ltm.c