Skip to content

Commit

Permalink
[bebop] Added the new Parrot Bebop
Browse files Browse the repository at this point in the history
  • Loading branch information
fvantienen authored and flixr committed Dec 3, 2014
1 parent e94c4b3 commit 9c14bbb
Show file tree
Hide file tree
Showing 18 changed files with 1,480 additions and 1 deletion.
39 changes: 39 additions & 0 deletions conf/Makefile.bebop
@@ -0,0 +1,39 @@
# Hey Emacs, this is a -*- makefile -*-
#
# Copyright (C) 2014 Freek van Tienen <freek.v.tienen@gmail.com>
#
# This file is part of paparazzi.
#
# paparazzi 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 2, or (at your option)
# any later version.
#
# paparazzi 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 paparazzi; see the file COPYING. If not, see
# <http://www.gnu.org/licenses/>.
#

#
# This Makefile uses the generic Makefile.linux and adds upload rules for the ARDrone2
#

include $(PAPARAZZI_SRC)/conf/Makefile.linux

DRONE = $(PAPARAZZI_SRC)/sw/ext/bebop.py

# Allow modules or other raw makefiles to add actions to the upload
upload_extra:


# Program the device and start it.
upload program: upload_extra $(OBJDIR)/$(TARGET).elf
$(Q)$(DRONE) --host=$(HOST) upload_file_and_run $(OBJDIR)/$(TARGET).elf $(SUB_DIR)

# Listing of phony targets.
.PHONY : upload_extra upload program
217 changes: 217 additions & 0 deletions conf/airframes/bebop.xml
@@ -0,0 +1,217 @@
<!DOCTYPE airframe SYSTEM "airframe.dtd">

<airframe name="bebop">

<firmware name="rotorcraft">
<target name="ap" board="bebop">
<subsystem name="telemetry" type="transparent_udp"/>
<subsystem name="radio_control" type="datalink"/>
</target>

<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
<subsystem name="radio_control" type="ppm"/>
</target>

<!--define name="USE_SONAR" value="TRUE"/-->

<!-- Subsystem section -->
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="bebop"/>
<subsystem name="imu" type="bebop"/>
<subsystem name="gps" type="furuno"/>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat"/>
<subsystem name="ins" type="extended"/>
</firmware>

<modules main_freq="512">
<load name="send_imu_mag_current.xml"/>
<load name="file_logger.xml">
<define name="FILE_LOGGER_PATH" value="\\\"/data/ftp/internal_000/\\\""/>
</load>
</modules>

<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="6000"/>
</commands>

<servos driver="Default">
<servo name="TOP_LEFT" no="0" min="3000" neutral="3000" max="12000"/>
<servo name="TOP_RIGHT" no="1" min="3000" neutral="3000" max="12000"/>
<servo name="BOTTOM_RIGHT" no="2" min="3000" neutral="3000" max="12000"/>
<servo name="BOTTOM_LEFT" no="3" min="3000" neutral="3000" max="12000"/>
</servos>

<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="255"/>
<define name="MAX_SATURATION_OFFSET" value="3*MAX_PPRZ"/>

<!-- Time cross layout (X), with order NW (CW), NE (CCW), SE (CW), SW (CCW) -->
<define name="ROLL_COEF" value="{ -256, 256, 256, -256 }"/>
<define name="PITCH_COEF" value="{ 256, 256, -256, -256 }"/>
<define name="YAW_COEF" value="{ 256, -256, 256, -256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>

<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="TOP_LEFT" value="motor_mixing.commands[0]"/>
<set servo="TOP_RIGHT" value="motor_mixing.commands[1]"/>
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[2]"/>
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[3]"/>
</command_laws>

<section name="IMU" prefix="IMU_">
<!-- Magneto calibration -->
<define name="MAG_X_NEUTRAL" value="18"/>
<define name="MAG_Y_NEUTRAL" value="157"/>
<define name="MAG_Z_NEUTRAL" value="49"/>
<define name="MAG_X_SENS" value="10.5007722373" integer="16"/>
<define name="MAG_Y_SENS" value="11.1147400462" integer="16"/>
<define name="MAG_Z_SENS" value="11.6479371722" integer="16"/>

<!-- Magneto current calibration -->
<define name="MAG_X_CURRENT_COEF" value="0.0"/>
<define name="MAG_Y_CURRENT_COEF" value="0.0"/>
<define name="MAG_Z_CURRENT_COEF" value="0.0"/>

<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>

<!-- local magnetic field -->
<!-- http://wiki.paparazziuav.org/wiki/Subsystem/ahrs#Local_Magnetic_Field -->
<section name="AHRS" prefix="AHRS_">
<!-- Toulouse -->
<!--define name="H_X" value="0.513081"/>
<define name="H_Y" value="-0.00242783"/>
<define name="H_Z" value="0.858336"/-->
<!-- Delft -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
</section>

<section name="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="2.2"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
</section>

<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>
<define name="DEADBAND_P" value="20"/>
<define name="DEADBAND_Q" value="20"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>

<!-- feedback -->
<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="350"/>

<define name="IGAIN_P" value="75"/>
<define name="IGAIN_Q" value="75"/>
<define name="IGAIN_R" value="50"/>

<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>

<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="45" unit="deg"/>
<define name="SP_MAX_THETA" value="45" unit="deg"/>
<define name="SP_MAX_R" value="300" unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="50"/>

<!-- reference -->
<define name="REF_OMEGA_P" value="450" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.9"/>
<define name="REF_MAX_P" value="600." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>

<define name="REF_OMEGA_Q" value="450" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.9"/>
<define name="REF_MAX_Q" value="600." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>

<define name="REF_OMEGA_R" value="450" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.9"/>
<define name="REF_MAX_R" value="600." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(8000.)"/>

<!-- feedback -->
<define name="PHI_PGAIN" value="650"/>
<define name="PHI_DGAIN" value="300"/>
<define name="PHI_IGAIN" value="0"/>

<define name="THETA_PGAIN" value="650"/>
<define name="THETA_DGAIN" value="300"/>
<define name="THETA_IGAIN" value="0"/>

<define name="PSI_PGAIN" value="4000"/>
<define name="PSI_DGAIN" value="350"/>
<define name="PSI_IGAIN" value="0"/>

<!-- feedforward -->
<define name="PHI_DDGAIN" value="0"/>
<define name="THETA_DDGAIN" value="0"/>
<define name="PSI_DDGAIN" value="0"/>
</section>

<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="283"/>
<define name="HOVER_KD" value="82"/>
<define name="HOVER_KI" value="13"/>
<define name="NOMINAL_HOVER_THROTTLE" value="0.655"/>
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
</section>

<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<!-- Good weather -->
<define name="MAX_BANK" value="20" unit="deg"/>
<!-- Bad weather -->
<!-- define name="MAX_BANK" value="32" unit="deg"/ -->
<define name="PGAIN" value="79"/>
<define name="DGAIN" value="100"/>
<define name="IGAIN" value="30"/>
</section>

<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{&quot;nw_motor&quot;, &quot;ne_motor&quot;, &quot;se_motor&quot;, &quot;sw_motor&quot;}"/>
<define name="JSBSIM_MODEL" value="&quot;simple_ardrone2&quot;"/>
<define name="JSBSIM_INIT" value="&quot;reset00&quot;"/>
<define name="SENSORS_PARAMS" value="&quot;nps_sensors_params_ardrone2.h&quot;"/>
</section>

<section name="AUTOPILOT">
<define name="MODE_STARTUP" value="AP_MODE_NAV"/>
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>

<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="9.7" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
39 changes: 39 additions & 0 deletions conf/boards/bebop.makefile
@@ -0,0 +1,39 @@
# Hey Emacs, this is a -*- makefile -*-
#
# bebop.makefile
#
# http://wiki.paparazziuav.org/wiki/Bebop
#

BOARD=bebop
BOARD_CFG=\"boards/$(BOARD).h\"

ARCH=linux
$(TARGET).ARCHDIR = $(ARCH)
# include conf/Makefile.bebop (with specific upload rules) instead of only Makefile.linux:
ap.MAKEFILE = bebop

# -----------------------------------------------------------------------
USER=foobar
HOST?=192.168.42.1
SUB_DIR=paparazzi
FTP_DIR=/data/ftp
TARGET_DIR=$(FTP_DIR)/$(SUB_DIR)
# -----------------------------------------------------------------------

# The datalink default uses UDP
MODEM_HOST ?= \"192.168.42.255\"

# The GPS sensor is connected internally
GPS_PORT ?= UART1
GPS_BAUD ?= B230400
$(TARGET).CFLAGS += -DUART1_DEV=\"/dev/ttyPA1\"

# -----------------------------------------------------------------------

# default LED configuration
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= 1
GPS_LED ?= none
SYS_TIME_LED ?= 0
11 changes: 11 additions & 0 deletions conf/conf_example.xml
Expand Up @@ -219,6 +219,17 @@
settings_modules=""
gui_color="blue"
/>
<aircraft
name="bebop"
ac_id="202"
airframe="airframes/bebop.xml"
radio="radios/cockpitSX.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_rate.xml settings/control/stabilization_att_int.xml"
settings_modules=""
gui_color="red"
/>
<aircraft
name="krooz_quad"
ac_id="23"
Expand Down
2 changes: 2 additions & 0 deletions conf/firmwares/rotorcraft.makefile
Expand Up @@ -125,6 +125,8 @@ else ifeq ($(BOARD)$(BOARD_TYPE), ardronesdk)
ns_srcs += $(SRC_BOARD)/electrical_dummy.c
else ifeq ($(BOARD)$(BOARD_TYPE), ardroneraw)
ns_srcs += $(SRC_BOARD)/electrical_raw.c
else ifeq ($(BOARD), bebop)
ns_srcs += $(SRC_BOARD)/electrical.c
endif

#
Expand Down
11 changes: 11 additions & 0 deletions conf/firmwares/subsystems/shared/actuators_bebop.makefile
@@ -0,0 +1,11 @@

# Actuator drivers for the bebop

BEBOP_ACTUATORS_I2C_DEV ?= i2c1
BEBOP_ACTUATORS_I2C_DEV_UPPER=$(shell echo $(BEBOP_ACTUATORS_I2C_DEV) | tr a-z A-Z)
BEBOP_ACTUATORS_I2C_DEV_LOWER=$(shell echo $(BEBOP_ACTUATORS_I2C_DEV) | tr A-Z a-z)

BEBOP_ACTUATORS_CFLAGS += -DBEBOP_ACTUATORS_I2C_DEV=$(BEBOP_ACTUATORS_I2C_DEV_LOWER) -DUSE_$(BEBOP_ACTUATORS_I2C_DEV_UPPER)=1

$(TARGET).CFLAGS += -DACTUATORS $(BEBOP_ACTUATORS_CFLAGS)
$(TARGET).srcs += $(SRC_BOARD)/actuators.c
9 changes: 9 additions & 0 deletions conf/firmwares/subsystems/shared/baro_board.makefile
Expand Up @@ -29,6 +29,15 @@ else ifeq ($(BOARD), navstik)
else ifeq ($(BOARD)$(BOARD_TYPE), ardroneraw)
BARO_BOARD_SRCS += $(SRC_BOARD)/baro_board.c

# Bebop baro
else ifeq ($(BOARD), bebop)
BARO_BOARD_CFLAGS += -DBARO_BOARD=BARO_MS5611_I2C -DBB_MS5611_SLAVE_ADDR=0x77
BARO_BOARD_CFLAGS += -DUSE_I2C1
BARO_BOARD_CFLAGS += -DBB_MS5611_I2C_DEV=i2c1
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_i2c.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_i2c.c

# Lisa/M baro
else ifeq ($(BOARD), lisa_m)
ifeq ($(BOARD_VERSION), 1.0)
Expand Down

0 comments on commit 9c14bbb

Please sign in to comment.