mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 09:22:18 +00:00
Working motors and mtd for CF2
This commit is contained in:
committed by
Lorenz Meier
parent
b65ff53b00
commit
9c8e56401b
@@ -7,48 +7,8 @@
|
||||
# @maintainer Tim Dyer <dyer.ti@gmail.com>
|
||||
#
|
||||
|
||||
# uorb start
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
# Params
|
||||
|
||||
# System status LEDs
|
||||
|
||||
# waypoint storage
|
||||
|
||||
# Sensors
|
||||
mpu9250 -R 12 start
|
||||
ak8963 start
|
||||
lps25h start
|
||||
sensors start
|
||||
|
||||
commander start
|
||||
|
||||
# Output mode
|
||||
crazyflie start
|
||||
|
||||
# MAVLINK
|
||||
# mavlink start -r 1200 -d /dev/ttyS***
|
||||
|
||||
# MAVTYPE
|
||||
param set MAV_TYPE 2
|
||||
|
||||
exit 1
|
||||
|
||||
set OUTPUT_DEV /dev/pwm_output0
|
||||
set MIXER_FILE /etc/mixers/quad_x.main.mix
|
||||
if mixer load $OUTPUT_DEV $MIXER_FILE
|
||||
then
|
||||
echo "[i] Mixer: $MIXER_FILE on $OUTPUT_DEV"
|
||||
else
|
||||
echo "[i] Error loading mixer: $MIXER_FILE"
|
||||
echo "ERROR: Could not load mixer: $MIXER_FILE" >> $LOG_FILE
|
||||
tone_alarm $TUNE_ERR
|
||||
fi
|
||||
|
||||
sh /etc/init.d/rc.mc_apps
|
||||
|
||||
# Navigator
|
||||
navigator start
|
||||
|
||||
# Boot complete
|
||||
mavlink boot_complete
|
||||
set OUTPUT_MODE crazyflie
|
||||
set USE_IO no
|
||||
|
||||
@@ -11,8 +11,8 @@ set(config_module_list
|
||||
drivers/led
|
||||
drivers/boards/crazyflie
|
||||
drivers/crazyflie
|
||||
drivers/mpu9250
|
||||
drivers/ak8963
|
||||
#drivers/mpu9250
|
||||
#drivers/ak8963
|
||||
drivers/lps25h
|
||||
drivers/gps
|
||||
# drivers/pwm_out_sim
|
||||
@@ -39,8 +39,10 @@ set(config_module_list
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
#modules/gpio_led
|
||||
modules/land_detector
|
||||
|
||||
modules/dummy
|
||||
@@ -51,18 +53,18 @@ set(config_module_list
|
||||
# Too high RAM usage due to static allocations
|
||||
# modules/attitude_estimator_ekf
|
||||
modules/attitude_estimator_q
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
# modules/segway # XXX Needs GCC 4.7 fix
|
||||
modules/fw_pos_control_l1
|
||||
modules/fw_att_control
|
||||
# modules/fw_pos_control_l1
|
||||
# modules/fw_att_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/vtol_att_control
|
||||
# modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
@@ -76,7 +78,6 @@ set(config_module_list
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/controllib
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
|
||||
@@ -84,8 +85,10 @@ set(config_module_list
|
||||
# Libraries
|
||||
#
|
||||
#lib/mathlib/CMSIS
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/rc
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
@@ -94,10 +97,12 @@ set(config_module_list
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
|
||||
#
|
||||
@@ -140,13 +145,16 @@ set(config_extra_builtin_cmds
|
||||
)
|
||||
|
||||
set(config_extra_libs
|
||||
${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a
|
||||
)
|
||||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
MAIN "sercon" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
MAIN "serdis" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
@@ -162,12 +162,16 @@
|
||||
* UARTs.
|
||||
*
|
||||
*/
|
||||
/* E_TX2 / E_RX2 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_1
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_1
|
||||
|
||||
/* E_TX1 / E_RX1 */
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_2
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_2
|
||||
|
||||
/* NRF51 via syslink */
|
||||
// TODO: Flow control?
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1
|
||||
|
||||
|
||||
@@ -433,7 +433,27 @@ CONFIG_WATCHDOG=y
|
||||
# CONFIG_INPUT is not set
|
||||
# CONFIG_LCD is not set
|
||||
# CONFIG_MMCSD is not set
|
||||
# CONFIG_MTD is not set
|
||||
CONFIG_MTD=y
|
||||
|
||||
#
|
||||
# MTD Configuration
|
||||
#
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
|
||||
#
|
||||
# MTD Device Drivers
|
||||
#
|
||||
# CONFIG_RAMMTD is not set
|
||||
CONFIG_MTD_AT24XX=y
|
||||
# CONFIG_MTD_AT45DB is not set
|
||||
# CONFIG_MTD_M25P is not set
|
||||
# CONFIG_MTD_SMART is not set
|
||||
# CONFIG_MTD_RAMTRON is not set
|
||||
# CONFIG_RAMTRON_FUJITSU is not set
|
||||
# CONFIG_MTD_SST25 is not set
|
||||
# CONFIG_MTD_SST39FV is not set
|
||||
# CONFIG_MTD_W25 is not set
|
||||
CONFIG_PIPES=y
|
||||
# CONFIG_PM is not set
|
||||
# CONFIG_POWER is not set
|
||||
@@ -527,7 +547,7 @@ CONFIG_CDCACM_RXBUFSIZE=300
|
||||
CONFIG_CDCACM_TXBUFSIZE=1000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_PRODUCTID=0x0016
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
CONFIG_CDCACM_VENDORSTR="Bitcraze AB"
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 Crazyflie v2.0"
|
||||
# CONFIG_USBMSC is not set
|
||||
# CONFIG_USBHOST is not set
|
||||
|
||||
@@ -37,6 +37,7 @@ px4_add_module(
|
||||
crazyflie_usb.c
|
||||
crazyflie_led.c
|
||||
crazyflie_timer_config.c
|
||||
crazyflie_i2c.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
|
||||
@@ -83,6 +83,8 @@ __BEGIN_DECLS
|
||||
#define PX4_I2C_BUS_ONBOARD_HZ 400000
|
||||
#define PX4_I2C_BUS_EXPANSION_HZ 400000
|
||||
|
||||
#define PX4_I2C_BUS_MTD PX4_I2C_BUS_EXPANSION
|
||||
|
||||
|
||||
|
||||
/* Devices on the onboard bus.
|
||||
@@ -127,6 +129,13 @@ __BEGIN_DECLS
|
||||
#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_2
|
||||
#define GPIO_TIM4_CH4OUT GPIO_TIM4_CH4OUT_1
|
||||
|
||||
#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_1
|
||||
#define GPIO_TIM2_CH4IN GPIO_TIM2_CH4IN_2
|
||||
#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_2
|
||||
#define GPIO_TIM4_CH4IN GPIO_TIM4_CH4IN_1
|
||||
|
||||
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
@@ -176,6 +185,20 @@ extern void stm32_usbinitialize(void);
|
||||
int nsh_archinitialize(void);
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_i2c_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to set I2C bus frequncies.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int board_i2c_initialize(void);
|
||||
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
|
||||
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
||||
@@ -145,6 +145,7 @@ __EXPORT int matherr(struct exception *e)
|
||||
|
||||
__EXPORT int nsh_archinitialize(void)
|
||||
{
|
||||
int result;
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
@@ -175,10 +176,10 @@ __EXPORT int nsh_archinitialize(void)
|
||||
|
||||
result = board_i2c_initialize();
|
||||
|
||||
// if (result != OK) {
|
||||
if (result != OK) {
|
||||
// up_ledon(LED_AMBER);
|
||||
// return -ENODEV;
|
||||
// }
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -42,11 +42,11 @@
|
||||
#include <stdint.h>
|
||||
|
||||
#include <stm32.h>
|
||||
#include <stm32_gpio_out.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_tim.h>
|
||||
|
||||
#include <drivers/stm32/drv_io_timer.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/stm32/drv_io_timer.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
@@ -55,7 +55,7 @@ __EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
.base = STM32_TIM2_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM2EN,
|
||||
.clock_freq = STM32_APB1_TIM2_CLKIN
|
||||
.clock_freq = STM32_APB1_TIM2_CLKIN,
|
||||
.first_channel_index = 0,
|
||||
.last_channel_index = 2,
|
||||
.handler = io_timer_handler0,
|
||||
@@ -65,7 +65,7 @@ __EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
.base = STM32_TIM4_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM4EN,
|
||||
.clock_freq = STM32_APB1_TIM4_CLKIN
|
||||
.clock_freq = STM32_APB1_TIM4_CLKIN,
|
||||
.first_channel_index = 3,
|
||||
.last_channel_index = 3,
|
||||
.handler = io_timer_handler1,
|
||||
|
||||
@@ -72,10 +72,6 @@
|
||||
#include <drivers/drv_rc_input.h>
|
||||
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/actuator_controls_0.h>
|
||||
#include <uORB/topics/actuator_controls_1.h>
|
||||
#include <uORB/topics/actuator_controls_2.h>
|
||||
#include <uORB/topics/actuator_controls_3.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
@@ -1078,10 +1074,18 @@ crazyflie_main(int argc, char *argv[])
|
||||
errx(0, "Crazyflie driver stopped");
|
||||
}
|
||||
|
||||
if (crazyflie_start() != OK) {
|
||||
errx(1, "failed to start the Crazyflie driver");
|
||||
if (!strcmp(verb, "start")) {
|
||||
if (crazyflie_start() == OK) {
|
||||
errx(0, "Crazyflie driver started");
|
||||
}
|
||||
else {
|
||||
errx(1, "failed to start the Crazyflie driver");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// TODO: Ensure driver is running
|
||||
|
||||
if (!strcmp(verb, "test")) {
|
||||
test();
|
||||
}
|
||||
|
||||
@@ -80,10 +80,15 @@ int mtd_main(int argc, char *argv[])
|
||||
static void ramtron_attach(void);
|
||||
#else
|
||||
|
||||
#ifndef PX4_I2C_BUS_ONBOARD
|
||||
# error PX4_I2C_BUS_ONBOARD not defined, cannot locate onboard EEPROM
|
||||
#ifndef PX4_I2C_BUS_MTD
|
||||
# ifdef PX4_I2C_BUS_ONBOARD
|
||||
# define PX4_I2C_BUS_MTD PX4_I2C_BUS_ONBOARD
|
||||
# else
|
||||
# error PX4_I2C_BUS_MTD and PX4_I2C_BUS_ONBOARD not defined, cannot locate onboard EEPROM
|
||||
# endif
|
||||
#endif
|
||||
|
||||
|
||||
static void at24xxx_attach(void);
|
||||
#endif
|
||||
static void mtd_start(char *partition_names[], unsigned n_partitions);
|
||||
@@ -225,7 +230,7 @@ static void
|
||||
at24xxx_attach(void)
|
||||
{
|
||||
/* find the right I2C */
|
||||
struct i2c_dev_s *i2c = px4_i2cbus_initialize(PX4_I2C_BUS_ONBOARD);
|
||||
struct i2c_dev_s *i2c = px4_i2cbus_initialize(PX4_I2C_BUS_MTD);
|
||||
/* this resets the I2C bus, set correct bus speed again */
|
||||
I2C_SETFREQUENCY(i2c, 400000);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user