jevois_mavlink (#2322)

This commit is contained in:
Christophe De Wagter
2018-09-11 11:28:31 +02:00
committed by Gautier Hattenberger
parent 929438c1eb
commit fa1d537b8b
7 changed files with 602 additions and 6 deletions
@@ -0,0 +1,221 @@
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<airframe name="bebop">
<description>Autonomous Race 2018 Bebop1
</description>
<firmware name="rotorcraft">
<target name="ap" board="bebop"/>
<target name="nps" board="pc">
<module name="fdm" type="jsbsim"/>
<module name="udp"/>
</target>
<define name="USE_SONAR" value="TRUE"/>
<!-- Subsystem section -->
<module name="telemetry" type="transparent_udp"/>
<module name="radio_control" type="datalink"/>
<module name="motor_mixing"/>
<module name="actuators" type="bebop"/>
<module name="imu" type="bebop"/>
<module name="gps" type="datalink"/>
<module name="stabilization" type="indi_simple"/>
<module name="stabilization" type="rate_indi"/>
<!--module name="stabilization" type="int_quat"/-->
<module name="ahrs" type="int_cmpl_quat">
<configure name="USE_MAGNETOMETER" value="FALSE"/> <!--TRUE-->
<configure name="USE_GPS" value="TRUE"/>
<define name="AHRS_USE_GPS_HEADING" value="TRUE"/><!--TRUE-->
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="TRUE"/>
</module>
<module name="ins" type="extended"/>
<!--module name="guidance" type="indi">
<define name="GUIDANCE_INDI_SPECIFIC_FORCE_GAIN" value="-500.0"/>
</module-->
<module name="geo_mag"/>
<module name="air_data"/>
<module name="send_imu_mag_current"/>
<!--module name="guidance_loop_velocity_autonomous_race"/-->
<module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</module>
<module name="sonar_bebop"/>
<module name="jevois_mavlink"/>
</firmware>
<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="TYPE" value="QUAD_X"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_get_motors_on(),FALSE,values)"/>
<set servo="TOP_LEFT" value="motor_mixing.commands[MOTOR_FRONT_LEFT]"/>
<set servo="TOP_RIGHT" value="motor_mixing.commands[MOTOR_FRONT_RIGHT]"/>
<set servo="BOTTOM_RIGHT" value="motor_mixing.commands[MOTOR_BACK_RIGHT]"/>
<set servo="BOTTOM_LEFT" value="motor_mixing.commands[MOTOR_BACK_LEFT]"/>
</command_laws>
<section name="AIR_DATA" prefix="AIR_DATA_">
<define name="CALC_AIRSPEED" value="FALSE"/>
<define name="CALC_TAS_FACTOR" value="FALSE"/>
<define name="CALC_AMSL_BARO" value="TRUE"/>
</section>
<include href="conf/airframes/tudelft/calibrations/bebop7.xml" />
<section name="AHRS" prefix="AHRS_">
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
<!-- Delft -->
<define name="H_X" value="0.3892503"/>
<define name="H_Y" value="0.0017972"/>
<define name="H_Z" value="0.9211303"/>
<define name="HEADING_UPDATE_GPS_MIN_SPEED" value="0"/>
<define name="GRAVITY_HEURISTIC_FACTOR" value="30"/><!-- was 0-->
</section>
<section name="IMU" prefix="IMU_">
<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="INS" prefix="INS_">
<define name="SONAR_MAX_RANGE" value="5"/>
<define name="SONAR_UPDATE_ON_AGL" value="TRUE"/>
</section>
<section name="RC_SETPOINT" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoint limits for attitude stabilization rc flight -->
<define name="SP_MAX_PHI" value="45" unit="deg"/>
<define name="SP_MAX_THETA" value="45" unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
</section>
<section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
<!-- control effectiveness -->
<!--define name="G1_P" value="0.0277"/>
<define name="G1_Q" value="0.0244"/>
<define name="G1_R" value="0.0007"/>
<define name="G2_R" value="0.10502"/-->
<!--define name="G1_P" value="0.03762"/>
<define name="G1_Q" value="0.031149"/>
<define name="G1_R" value="0.00094"/>
<define name="G2_R" value="0.081811"/-->
<define name="G1_P" value="0.04762"/>
<define name="G1_Q" value="0.041149"/>
<define name="G1_R" value="0.00194"/>
<define name="G2_R" value="0.151811"/>
<!-- reference acceleration for attitude control -->
<define name="REF_ERR_P" value="400.0"/><!--600-->
<define name="REF_ERR_Q" value="400.0"/>
<define name="REF_ERR_R" value="400.0"/>
<define name="REF_RATE_P" value="28.0"/>
<define name="REF_RATE_Q" value="28.0"/>
<define name="REF_RATE_R" value="28.0"/>
<!--Maxium yaw rate, to avoid instability-->
<define name="MAX_R" value="120.0" unit="deg/s"/>
<!-- second order filter parameters -->
<define name="FILT_OMEGA" value="50.0"/>
<define name="FILT_ZETA" value="0.55"/>
<define name="FILT_OMEGA_R" value="50.0"/>
<define name="FILT_ZETA_R" value="0.55"/>
<!-- first order actuator dynamics -->
<define name="ACT_DYN_P" value="0.1"/>
<define name="ACT_DYN_Q" value="0.1"/>
<define name="ACT_DYN_R" value="0.1"/>
<!-- Adaptive Learning Rate -->
<define name="USE_ADAPTIVE" value="FALSE"/>
<define name="ADAPTIVE_MU" value="0.0001"/>
</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="20"/>
<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"/>
<define name="REF_MAX_SPEED" value="2" unit="m/s"/>
<!-- 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="NAVIGATION" prefix="NAV_">
<define name="CLIMB_VSPEED" value="2.5"/>
<define name="DESCEND_VSPEED" value="-1.0"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="nw_motor, ne_motor, se_motor, sw_motor" type="string[]"/>
<define name="JSBSIM_MODEL" value="simple_x_quad_ccw" type="string"/>
<define name="SENSORS_PARAMS" value="nps_sensors_params_default.h" type="string"/>
</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_MODULE"/>
<define name="NO_RC_THRUST_LIMIT" value="TRUE"/>
</section>
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="8700"/>
<define name="CATASTROPHIC_BAT_LEVEL" value="9.9" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="11.0" unit="V"/>
<define name="LOW_BAT_LEVEL" value="11.1" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>
@@ -34,16 +34,14 @@
<define name="GUIDANCE_INDI_THRUST_DYNAMICS" value="0.1"/>
<define name="GUIDANCE_INDI_RC_DEBUG" value="FALSE"/>
</module>
</firmware>
<modules main_freq="512">
<module name="geo_mag"/>
<module name="air_data"/>
<module name="send_imu_mag_current"/>
<!--module name="logger_file">
<define name="FILE_LOGGER_PATH" value="/data/ftp/internal_000"/>
</module-->
</modules>
</firmware>
<commands>
<axis name="PITCH" failsafe_value="0"/>
+27
View File
@@ -0,0 +1,27 @@
<!DOCTYPE module SYSTEM "module.dtd">
<module name="jevois_mavlink" dir="sensors/cameras">
<doc>
<description>Send sensor data to jevois and read commands from jevois using MAVLINK messages.</description>
</doc>
<header>
<file name="jevois_mavlink.h"/>
</header>
<init fun="jevois_mavlink_init()"/>
<periodic fun="jevois_mavlink_periodic()" freq="60"/>
<periodic fun="jevois_mavlink_filter_periodic()"/>
<event fun="jevois_mavlink_event()"/>
<makefile target="!sim|nps">
<file name="jevois_mavlink.c"/>
<configure name="JEVOIS_UART" default="uart2" case="upper|lower"/>
<configure name="JEVOIS_BAUD" default="B115200" />
<define name="USE_$(JEVOIS_UART_UPPER)"/>
<define name="JEVOIS_DEV" value="$(JEVOIS_UART_LOWER)"/>
<define name="$(JEVOIS_UART_UPPER)_BAUD" value="$(JEVOIS_BAUD)"/>
</makefile>
</module>
+14 -3
View File
@@ -129,7 +129,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/video_rtp_stream.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
settings_modules="modules/bebop_ae_awb.xml modules/video_rtp_stream.xml modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_float_mlkf.xml modules/stabilization_int_quat.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffbc3bce5b"
/>
<aircraft
@@ -452,9 +452,9 @@
gui_color="red"
/>
<aircraft
name="autonomous_race"
name="autonomous_race_2017"
ac_id="8"
airframe="airframes/tudelft/bebop_autonomous_race.xml"
airframe="airframes/tudelft/bebop_autonomous_race_2017.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
@@ -463,6 +463,17 @@
gui_color="#ffffbc3bce5b"
release="3fc18944dc13632f0ace7c7035dfc8286be88668"
/>
<aircraft
name="autonomous_race_2018"
ac_id="121"
airframe="airframes/tudelft/bebop_autonomous_race_2018.xml"
radio="radios/dummy.xml"
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
settings_modules="modules/air_data.xml modules/geo_mag.xml modules/ins_extended.xml modules/ahrs_int_cmpl_quat.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml"
gui_color="#ffffbc3bce5b"
/>
<aircraft
name="bebop2_22"
ac_id="22"
@@ -0,0 +1,246 @@
/*
* Copyright (C) MAVLab
*
* 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/>.
*/
/**
* @file "modules/sensors/cameras/jevois_mavlink.c"
* @author MAVLab
* Send sensor data to jevois and read commands from jevois
*/
#include "modules/sensors/cameras/jevois_mavlink.h"
#define DEBUG_PRINT printf
#include <stdio.h>
/*
* MavLink protocol
*/
#include <mavlink/mavlink_types.h>
#include "mavlink/paparazzi/mavlink.h"
#include "subsystems/imu.h"
#include "autopilot.h"
mavlink_system_t mavlink_system;
#ifndef MAVLINK_SYSID
#define MAVLINK_SYSID 1
#endif
static void mavlink_send_heartbeat(void);
static void mavlink_send_attitude(void);
static void mavlink_send_highres_imu(void);
static void mavlink_send_set_mode(void);
/*
* Exported data
*/
mavlink_manual_setpoint_t jevois_mavlink_manual_setpoint;
mavlink_debug_t jevois_mavlink_debug;
mavlink_altitude_t jevois_mavlink_altitude;
mavlink_attitude_t jevois_mavlink_attitude;
mavlink_local_position_ned_t jevois_mavlink_local_position;
/*
* Paparazzi Module functions : filter functions
*/
#include "filters/low_pass_filter.h"
Butterworth2LowPass_int ax_filtered;
Butterworth2LowPass_int ay_filtered;
Butterworth2LowPass_int az_filtered;
void jevois_mavlink_filter_periodic(void)
{
update_butterworth_2_low_pass_int(&ax_filtered, imu.accel.x);
update_butterworth_2_low_pass_int(&ay_filtered, imu.accel.y);
update_butterworth_2_low_pass_int(&az_filtered, imu.accel.z);
}
void jevois_mavlink_filter_init(void);
void jevois_mavlink_filter_init(void)
{
init_butterworth_2_low_pass_int(&ax_filtered, 20.0, 1.0 / ((float)MODULES_FREQUENCY), imu.accel_unscaled.x);
init_butterworth_2_low_pass_int(&ay_filtered, 20.0, 1.0 / ((float)MODULES_FREQUENCY), imu.accel_unscaled.y);
init_butterworth_2_low_pass_int(&az_filtered, 20.0, 1.0 / ((float)MODULES_FREQUENCY), imu.accel_unscaled.z);
}
/*
* Paparazzi Module functions : communications
*/
void jevois_mavlink_init(void)
{
mavlink_system.sysid = MAVLINK_SYSID; // System ID, 1-255
mavlink_system.compid = 0; // Component/Subsystem ID, 1-255
jevois_mavlink_filter_init();
}
void jevois_mavlink_periodic(void)
{
RunOnceEvery(100, mavlink_send_heartbeat());
RunOnceEvery(2, mavlink_send_attitude());
RunOnceEvery(1, mavlink_send_highres_imu());
RunOnceEvery(1, mavlink_send_set_mode());
}
void jevois_mavlink_event(void)
{
mavlink_message_t msg;
mavlink_status_t status;
while (MAVLinkChAvailable()) {
uint8_t c = MAVLinkGetch();
if (mavlink_parse_char(MAVLINK_COMM_1, c, &msg, &status)) {
//printf("msg.msgid is %d\n",msg.msgid);
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT: {
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&msg, &heartbeat);
// do something with heartbeat variable
}
break;
case MAVLINK_MSG_ID_ATTITUDE: {
// read attitude command from Jevois
mavlink_msg_attitude_decode(&msg, &jevois_mavlink_attitude);
DEBUG_PRINT("[jevois mavlink] phi_cmd = %f\n", DegOfRad(jevois_mavlink_attitude.roll));
DEBUG_PRINT("[jevois mavlink] theta_cmd = %f\n", DegOfRad(jevois_mavlink_attitude.pitch));
DEBUG_PRINT("[jevois mavlink] psi_cmd = %f\n", DegOfRad(jevois_mavlink_attitude.yaw));
}
break;
case MAVLINK_MSG_ID_ALTITUDE: {
mavlink_msg_altitude_decode(&msg, &jevois_mavlink_altitude);
DEBUG_PRINT("[jevois mavlink] desired altitude is %f", jevois_mavlink_altitude.altitude_relative);
}
break;
case MAVLINK_MSG_ID_DEBUG: {
mavlink_msg_debug_decode(&msg, &jevois_mavlink_debug);
DEBUG_PRINT("[jevois mavlink] debug value is %f", jevois_mavlink_debug.value);
DEBUG_PRINT("[jevois mavlink] debug ind is %d", jevois_mavlink_debug.ind);
}
break;
case MAVLINK_MSG_ID_MANUAL_SETPOINT: {
mavlink_msg_manual_setpoint_decode(&msg, &jevois_mavlink_manual_setpoint);
DEBUG_PRINT("[jevois mavlink] phi_cmd = %f\n", DegOfRad(jevois_mavlink_manual_setpoint.roll));
DEBUG_PRINT("[jevois mavlink] theta_cmd = %f\n", DegOfRad(jevois_mavlink_manual_setpoint.pitch));
DEBUG_PRINT("[jevois mavlink] psi_cmd = %f\n", DegOfRad(jevois_mavlink_manual_setpoint.yaw));
DEBUG_PRINT("[jevois mavlink] alt_cmd = %f\n", jevois_mavlink_manual_setpoint.thrust);
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION_NED: {
mavlink_msg_local_position_ned_decode(&msg, &jevois_mavlink_local_position);
}
break;
}
}
}
}
/////////////////////////////
#include "state.h"
#include "mcu_periph/sys_time.h"
static void mavlink_send_attitude(void)
{
mavlink_msg_attitude_send(MAVLINK_COMM_0,
get_sys_time_msec(),
stateGetNedToBodyEulers_f()->phi, // Phi
stateGetNedToBodyEulers_f()->theta, // Theta
stateGetNedToBodyEulers_f()->psi, // Psi
stateGetBodyRates_f()->p, // p
stateGetBodyRates_f()->q, // q
stateGetBodyRates_f()->r); // r
MAVLinkSendMessage();
}
static void mavlink_send_set_mode(void)
{
mavlink_msg_set_mode_send(MAVLINK_COMM_0,
get_sys_time_msec(),
0, //autopilotMode.currentMode,
0
);
MAVLinkSendMessage();
}
static void mavlink_send_heartbeat(void)
{
mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
MAV_TYPE_FIXED_WING,
MAV_AUTOPILOT_PPZ,
MAV_MODE_FLAG_AUTO_ENABLED,
0, // custom_mode
MAV_STATE_CALIBRATING);
MAVLinkSendMessage();
}
static void mavlink_send_highres_imu(void)
{
mavlink_msg_highres_imu_send(MAVLINK_COMM_0,
get_sys_time_msec(),
get_butterworth_2_low_pass_int(&ax_filtered) / 1024.0,
get_butterworth_2_low_pass_int(&ay_filtered) / 1024.0,
get_butterworth_2_low_pass_int(&az_filtered) / 1024.0,
stateGetBodyRates_f()->p,
stateGetBodyRates_f()->q,
stateGetBodyRates_f()->r,
stateGetNedToBodyEulers_f()->phi,
stateGetNedToBodyEulers_f()->theta,
stateGetNedToBodyEulers_f()->psi,
0,
0,
0,
0,
0);
MAVLinkSendMessage();
}
@@ -0,0 +1,93 @@
/*
* Copyright (C) MAVLab
*
* 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/>.
*/
/**
* @file "modules/sensors/cameras/jevois_mavlink.h"
* @author MAVLab
* Send sensor data to jevois and read commands from jevois
*/
#ifndef JEVOIS_MAVLINK_H
#define JEVOIS_MAVLINK_H
/*
* Paparazzi UART over USB
*/
#include "mcu_periph/uart.h"
#ifndef JEVOIS_DEV
#define JEVOIS_DEV uart2
#endif
#define MAVLinkDev (&(JEVOIS_DEV).device)
#define MAVLinkTransmit(c) MAVLinkDev->put_byte(MAVLinkDev->periph, 0, c)
#define MAVLinkChAvailable() MAVLinkDev->char_available(MAVLinkDev->periph)
#define MAVLinkGetch() MAVLinkDev->get_byte(MAVLinkDev->periph)
#define MAVLinkSendMessage() MAVLinkDev->send_message(MAVLinkDev->periph, 0)
/*
* MavLink protocol
*/
#include <mavlink/mavlink_types.h>
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#define MAVLINK_ALIGNED_FIELDS 0
extern mavlink_system_t mavlink_system;
static inline void comm_send_ch(mavlink_channel_t chan __attribute__((unused)), uint8_t ch)
{
// Send bytes
MAVLinkTransmit(ch);
}
/*
* Paparazzi Module functions
*/
extern void jevois_mavlink_init(void);
extern void jevois_mavlink_periodic(void);
extern void jevois_mavlink_filter_periodic(void);
extern void jevois_mavlink_event(void);
#endif