Skip to content

Commit

Permalink
Merge pull request #851 from paparazzi/spektrum_sim
Browse files Browse the repository at this point in the history
[radio_control] spektrum for nps/sim

OCaml sim always uses the radio.xml file and sends ppm values in usec.
So for the time beeing you need to use the spektrum.xml radio file for the sim target if you really want to use the RC in the simple OCaml sim.

closes #503
  • Loading branch information
flixr committed Oct 12, 2014
2 parents 1532734 + 0a612a0 commit 063e75e
Show file tree
Hide file tree
Showing 11 changed files with 200 additions and 40 deletions.
12 changes: 6 additions & 6 deletions conf/airframes/examples/bumblebee_quad.xml
Expand Up @@ -20,19 +20,19 @@

<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<subsystem name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</subsystem>
<!-- MPU6000 is configured to output data at 2kHz, but polled at 512Hz PERIODIC_FREQUENCY -->
</target>

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

<subsystem name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_FLAP"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</subsystem>

<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
Expand Down
10 changes: 6 additions & 4 deletions conf/airframes/examples/lisa_asctec.xml
Expand Up @@ -176,13 +176,9 @@
<firmware name="rotorcraft">
<target name="ap" board="lisa_l_1.1">
<!-- <define name="ACTUATORS_START_DELAY" value="1"/> -->
<subsystem name="radio_control" type="spektrum"/>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="asctec_v2"/>
<subsystem name="telemetry" type="transparent"/>
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/>
<define name="USE_I2C_ACTUATORS_REBOOT_HACK"/>
</target>
<target name="nps" board="pc">
Expand All @@ -192,6 +188,12 @@
<subsystem name="actuators" type="mkk"/>
</target>

<subsystem name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_AUX2"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_CONTROL_SPEKTRUM_SIGNS" value="\{1,1,-1,1,-1,-1,-1,1,1,1,1,1\}"/>
</subsystem>

<subsystem name="imu" type="b2_v1.1"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_euler"/>
Expand Down
10 changes: 5 additions & 5 deletions conf/airframes/examples/quadrotor_lisa_m_2_pwm_spektrum.xml
Expand Up @@ -12,18 +12,18 @@

<firmware name="rotorcraft">
<target name="ap" board="lisa_m_2.0">
<subsystem name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_AUX1"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</subsystem>
<!-- MPU6000 is configured to output data at 2kHz, but polled at 512Hz PERIODIC_FREQUENCY -->
</target>

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

<subsystem name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_AUX1"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</subsystem>

<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
Expand Down
10 changes: 5 additions & 5 deletions conf/airframes/examples/quadrotor_lisa_mx.xml
Expand Up @@ -12,18 +12,18 @@

<firmware name="rotorcraft">
<target name="ap" board="lisa_mx_2.1">
<subsystem name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_AUX1"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</subsystem>
<!-- MPU6000 is configured to output data at 2kHz, but polled at 512Hz PERIODIC_FREQUENCY -->
</target>

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

<subsystem name="radio_control" type="spektrum">
<define name="RADIO_MODE" value="RADIO_AUX1"/>
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
</subsystem>

<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
Expand Down
8 changes: 4 additions & 4 deletions conf/airframes/examples/quadrotor_navstik.xml
Expand Up @@ -12,18 +12,18 @@

<firmware name="rotorcraft">
<target name="ap" board="navstik_1.0">
<subsystem name="radio_control" type="spektrum"/>
<configure name="ACTUATORS_ASCTEC_V2_I2C_DEV" value="i2c3"/>
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_MODE" value="RADIO_AUX1"/>
<define name="ACTUATORS_START_DELAY" value="1"/>
</target>

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

<subsystem name="radio_control" type="spektrum">
<define name="RADIO_KILL_SWITCH" value="RADIO_GEAR"/>
<define name="RADIO_MODE" value="RADIO_AUX1"/>
</subsystem>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="asctec_v2"/>
<subsystem name="telemetry" type="xbee_api"/>
Expand Down
Expand Up @@ -31,8 +31,8 @@ RC_SRCS += $(SRC_SUBSYSTEMS)/radio_control.c \
$(SRC_SUBSYSTEMS)/radio_control/spektrum.c \
$(SRC_ARCH)/subsystems/radio_control/spektrum_arch.c

ap.CFLAGS += $(RC_CFLAGS)
ap.srcs += $(RC_SRCS)
$(TARGET).CFLAGS += $(RC_CFLAGS)
$(TARGET).srcs += $(RC_SRCS)

test_radio_control.CFLAGS += $(RC_CFLAGS)
test_radio_control.srcs += $(RC_SRCS)
20 changes: 10 additions & 10 deletions conf/radios/spektrum.xml
Expand Up @@ -44,14 +44,14 @@

<!DOCTYPE radio SYSTEM "radio.dtd">
<!--<serial name="Spektrum Serial" data_min="900pulse_type="NEGATIVE">-->
<radio name="JR XP903" data_min="900" data_max="2100" sync_min ="5000" sync_max ="15000" pulse_type="NEGATIVE">
<channel ctl="left_stick_vert" function="THROTTLE" max="2050" neutral="950" min="950" average="0"/>
<channel ctl="right_stick_horiz" function="ROLL" min="2050" neutral="1500" max="950" average="0"/>
<channel ctl="right_stick_vert" function="PITCH" min="2050" neutral="1500" max="950" average="0"/>
<channel ctl="left_stick_horiz" function="YAW" min="950" neutral="1500" max="2050" average="0"/>
<channel ctl="switch_g" function="UNUSED" min="2050" neutral="1500" max="948" average="1"/>
<channel ctl="switch_C" function="MODE" min="2050" neutral="1500" max="950" average="1"/>
<channel ctl="aux2" function="KILL" min="2050" neutral="1496" max="948" average="1"/>
<channel ctl="aux3" function="AUX3" min="2050" neutral="1500" max="950" average="1"/>
<channel ctl="aux4" function="AUX4" min="2050" neutral="1496" max="948" average="1"/>
<radio name="fake spektrum" data_min="900" data_max="2100" sync_min ="5000" sync_max ="15000" pulse_type="NEGATIVE">
<channel ctl="left_stick_vert" function="THROTTLE" min="1000" neutral="1000" max="2000" average="0"/>
<channel ctl="right_stick_horiz" function="ROLL" min="2000" neutral="1500" max="1000" average="0"/>
<channel ctl="right_stick_vert" function="PITCH" min="2000" neutral="1500" max="1000" average="0"/>
<channel ctl="left_stick_horiz" function="YAW" min="2000" neutral="1500" max="1000" average="0"/>
<channel ctl="aux1" function="GEAR" min="1000" neutral="1500" max="2000" average="1"/>
<channel ctl="aux2" function="AUX1" min="1000" neutral="1500" max="2000" average="1"/>
<channel ctl="aux2" function="AUX2" min="1000" neutral="1500" max="2000" average="1"/>
<channel ctl="aux3" function="AUX3" min="1000" neutral="1500" max="2000" average="1"/>
<channel ctl="aux4" function="AUX4" min="1000" neutral="1500" max="2000" average="1"/>
</radio>
98 changes: 98 additions & 0 deletions sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c
@@ -0,0 +1,98 @@
/*
* Copyright (C) 2010-2012 The Paparazzi Team
*
* 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, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/

/**
* @file arch/sim/spektrum_arch.c
*
* Simulator implementation for spektrum radio control.
*
*/

#include "subsystems/radio_control.h"
#include "subsystems/radio_control/spektrum.h"

#include <inttypes.h>

#if USE_NPS
#include "nps_radio_control.h"
#elif !USE_JSBSIM
#include <caml/mlvalues.h>
#endif

static bool_t spektrum_available;

void radio_control_spektrum_try_bind(void) {}

void radio_control_impl_init(void)
{
spektrum_available = FALSE;
}
void RadioControlEventImp(void (*frame_handler)(void) ) {
if (spektrum_available) {
radio_control.frame_cpt++;
radio_control.time_since_last_frame = 0;
radio_control.status = RC_OK;
(*frame_handler)();
}
spektrum_available = FALSE;
}

#if USE_NPS
#ifdef RADIO_CONTROL
void radio_control_feed(void) {
radio_control.values[RADIO_ROLL] = nps_radio_control.roll * MAX_PPRZ;
radio_control.values[RADIO_PITCH] = nps_radio_control.pitch * MAX_PPRZ;
radio_control.values[RADIO_YAW] = nps_radio_control.yaw * MAX_PPRZ;
radio_control.values[RADIO_THROTTLE] = nps_radio_control.throttle * MAX_PPRZ;
radio_control.values[RADIO_MODE] = nps_radio_control.mode * MAX_PPRZ;
spektrum_available = TRUE;
}
#else //RADIO_CONTROL
void radio_control_feed(void) {}
#endif //RADIO_CONTROL

#elif !USE_JSBSIM // not NPS and not JSBSIM -> simple ocaml sim
#ifdef RADIO_CONTROL
value update_rc_channel(value c, value v) {
// OCaml sim sends ppm values read from radio xml
//assume "ppm" value range from 1000 to 2000 for now.. like in fake spektrum.xml
if (Int_val(c) == 0) {
// throttle channel has neutral at 1000
radio_control.values[Int_val(c)] = (Double_val(v) - 1000.0) / 1000 * MAX_PPRZ;
}
else {
// all other channels at 1500
radio_control.values[Int_val(c)] = (Double_val(v) - 1500.0) / 500 * MAX_PPRZ;
}
return Val_unit;
}

value send_ppm(value unit) {
spektrum_available = TRUE;
return unit;
}
#else // RADIO_CONTROL
value update_rc_channel(value c __attribute__ ((unused)), value v __attribute__ ((unused))) {
return Val_unit;
}
value send_ppm(value unit) {return unit;}
#endif // RADIO_CONTROL
#endif // USE_NPS
64 changes: 64 additions & 0 deletions sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.h
@@ -0,0 +1,64 @@
/*
* Copyright (C) 2010 Eric Parsonage <eric@eparsonage.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, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/

#ifndef RADIO_CONTROL_SPEKTRUM_ARCH_H
#define RADIO_CONTROL_SPEKTRUM_ARCH_H


/*
* All Spektrum and JR 2.4 GHz transmitters
* have the same channel assignments.
*/


#ifndef RADIO_CONTROL_NB_CHANNEL
#define RADIO_CONTROL_NB_CHANNEL 12
#endif

/* channel assignments */
#define RADIO_THROTTLE 0
#define RADIO_ROLL 1
#define RADIO_PITCH 2
#define RADIO_YAW 3
#define RADIO_GEAR 4
#define RADIO_FLAP 5
#define RADIO_AUX1 5
#define RADIO_AUX2 6
#define RADIO_AUX3 7
#define RADIO_AUX4 8
#define RADIO_AUX5 9
#define RADIO_AUX6 10
#define RADIO_AUX7 11

/* really for a 9 channel transmitter
we would swap the order of these */
#ifndef RADIO_MODE
#define RADIO_MODE RADIO_GEAR
#endif

extern void RadioControlEventImp(void (*_received_frame_handler)(void));

#if USE_NPS
extern void radio_control_feed(void);
#endif

#endif /* RADIO_CONTROL_SPEKTRUM_ARCH_H */
2 changes: 0 additions & 2 deletions sw/simulator/nps/nps_autopilot_fixedwing.c
Expand Up @@ -95,12 +95,10 @@ void nps_autopilot_run_step(double time) {

nps_electrical_run_step(time);

#ifdef RADIO_CONTROL_TYPE_PPM
if (nps_radio_control_available(time)) {
radio_control_feed();
Fbw(event_task);
}
#endif

if (nps_sensors_gyro_available()) {
imu_feed_gyro_accel();
Expand Down
2 changes: 0 additions & 2 deletions sw/simulator/nps/nps_autopilot_rotorcraft.c
Expand Up @@ -82,12 +82,10 @@ void nps_autopilot_run_step(double time) {

nps_electrical_run_step(time);

#ifdef RADIO_CONTROL_TYPE_PPM
if (nps_radio_control_available(time)) {
radio_control_feed();
main_event();
}
#endif

if (nps_sensors_gyro_available()) {
imu_feed_gyro_accel();
Expand Down

0 comments on commit 063e75e

Please sign in to comment.