mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-10 06:59:54 +08:00
*** empty log message ***
This commit is contained in:
@@ -166,14 +166,27 @@
|
||||
</section>
|
||||
|
||||
|
||||
<section name="GUIDANCE_V" prefix="BOOZ2_GUIDANCE_V_">
|
||||
<section name="GUIDANCE_V" prefix="BOOZ2_GUIDANCE_V_">
|
||||
<define name="HOVER_POWER" value="60"/>
|
||||
<define name="HOVER_KP" value="-200"/>
|
||||
<define name="HOVER_KD" value="-100"/>
|
||||
<define name="HOVER_KI" value="0"/>
|
||||
<define name="HOVER_KI" value="-50"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="GUIDANCE_H" prefix="BOOZ2_GUIDANCE_H_">
|
||||
<define name="PGAIN" value="-100"/>
|
||||
<define name="DGAIN" value="-100"/>
|
||||
<define name="IGAIN" value="-0"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="BAT">
|
||||
<define name="MILLIAMP_PER_PERCENT" value="0.86"/>
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
</section>
|
||||
|
||||
|
||||
|
||||
<makefile>
|
||||
|
||||
|
||||
@@ -16,7 +16,8 @@ main.TARGETDIR = mb
|
||||
main.CFLAGS += -DCONFIG=\"conf_motor_bench.h\" -I$(MB)
|
||||
main.srcs = $(MB)/main_motor_bench.c
|
||||
|
||||
main.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./250.)'
|
||||
main.CFLAGS += -DPERIODIC_TASK_FREQ='250.'
|
||||
main.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./PERIODIC_TASK_FREQ)'
|
||||
main.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
|
||||
|
||||
main.CFLAGS += -DLED
|
||||
@@ -37,6 +38,7 @@ main.CFLAGS += -DUSE_TWI_CONTROLLER
|
||||
main.CFLAGS += -DI2C_SCLL=100 -DI2C_SCLH=100
|
||||
#main.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c $(MB)/mb_twi_controller.c
|
||||
main.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c $(MB)/mb_twi_controller_asctech.c
|
||||
#main.srcs += i2c.c $(SRC_ARCH)/i2c_hw.c $(MB)/mb_twi_controller_mkk.c
|
||||
|
||||
main.CFLAGS += -DMB_TACHO
|
||||
main.srcs += $(MB)/mb_tacho.c
|
||||
@@ -49,6 +51,8 @@ main.CFLAGS += -DMB_SCALE
|
||||
main.srcs += $(MB)/mb_scale.c
|
||||
|
||||
main.srcs += $(MB)/mb_modes.c
|
||||
main.srcs += $(MB)/mb_static.c
|
||||
main.srcs += $(MB)/mb_mode_fixed_rpm.c
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -19,16 +19,17 @@ tunnel.srcs += $(SRC_ARCH)/uart_tunnel.c
|
||||
ARCHI=arm7
|
||||
|
||||
FLASH_MODE = IAP
|
||||
PT_ANT = antenna
|
||||
|
||||
main.ARCHDIR = $(ARCHI)
|
||||
main.ARCH = arm7tdmi
|
||||
main.TARGET = main
|
||||
main.TARGETDIR = main
|
||||
|
||||
main.CFLAGS += -DCONFIG=\"conf_demo.h\"
|
||||
main.srcs = main_pan_tilt_antenna.c
|
||||
main.CFLAGS += -DCONFIG=\"conf_demo.h\" -I$(PT_ANT)
|
||||
main.srcs = $(PT_ANT)/pt_ant_main.c
|
||||
|
||||
main.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1e-1)'
|
||||
main.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1.66666667e-2)'
|
||||
main.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c
|
||||
|
||||
main.CFLAGS += -DLED
|
||||
@@ -39,17 +40,17 @@ main.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B38400
|
||||
main.srcs += $(SRC_ARCH)/uart_hw.c
|
||||
|
||||
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart0
|
||||
main.srcs += downlink.c pprz_transport.c
|
||||
main.srcs += downlink.c pprz_transport.c $(PT_ANT)/pt_ant_telemetry.c
|
||||
|
||||
main.CFLAGS += -DDATALINK=PPRZ -DPPRZ_UART=Uart0
|
||||
main.srcs += pt_ant_datalink.c
|
||||
main.srcs += $(PT_ANT)/pt_ant_datalink.c
|
||||
|
||||
main.srcs += pt_ant_motors.c
|
||||
main.srcs += $(PT_ANT)/pt_ant_motors.c
|
||||
|
||||
main.CFLAGS += -I2C_BUF_LEN=32
|
||||
main.srcs += pt_ant_sensors.c AMI601.c i2c.c $(SRC_ARCH)/i2c_hw.c
|
||||
main.CFLAGS += -DUSE_AMI601 -DI2C_BUF_LEN=32
|
||||
main.srcs += AMI601.c i2c.c $(SRC_ARCH)/i2c_hw.c
|
||||
|
||||
main.srcs += pt_ant_estimator.c
|
||||
#main.srcs += pt_ant_estimator.c
|
||||
|
||||
main.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B9600
|
||||
#main.CFLAGS += -DGPS -DUBX -DGPS_LINK=Uart1
|
||||
|
||||
@@ -83,7 +83,7 @@ ap.ARCH = arm7tdmi
|
||||
ap.TARGET = ap
|
||||
ap.TARGETDIR = ap
|
||||
|
||||
#ap.CFLAGS += -DKILL_MOTORS
|
||||
ap.CFLAGS += -DKILL_MOTORS
|
||||
|
||||
ap.CFLAGS += -DCONFIG=\"booz2_board.h\" -I$(BOOZ_ARCH) -I$(BOOZ_PRIV) -I$(BOOZ_PRIV_ARCH)
|
||||
ap.srcs += $(BOOZ_PRIV)/booz2_main.c
|
||||
|
||||
@@ -1078,6 +1078,7 @@
|
||||
<field name="cmd_y" type="int32"/>
|
||||
<field name="cmd_phi" type="int32"/>
|
||||
<field name="cmd_theta" type="int32"/>
|
||||
<field name="cmd_psi" type="int32"/>
|
||||
</message>
|
||||
|
||||
|
||||
|
||||
@@ -3,8 +3,9 @@
|
||||
<settings>
|
||||
<dl_settings>
|
||||
<dl_settings name="trim">
|
||||
<dl_setting var="mb_modes_mode" min="0" step="1" max="4" module="mb_modes" handler="SetMode"/>
|
||||
<dl_setting var="mb_modes_mode" min="0" step="1" max="6" module="mb_modes" handler="SetMode"/>
|
||||
</dl_settings>
|
||||
|
||||
<dl_settings name="twi_asctech">
|
||||
<dl_setting var="mb_twi_controller_asctech_command_type" min="0" step="1" max="3"
|
||||
module="mb_twi_controller_asctech" handler="SetCommand"/>
|
||||
@@ -12,5 +13,14 @@
|
||||
module="mb_twi_controller_asctech" handler="SetAddr"/>
|
||||
</dl_settings>
|
||||
|
||||
<dl_settings name="scale">
|
||||
<dl_setting var="mb_scale_neutral" min="2940000" step="100" max="2950000" module="mb_scale"/>
|
||||
<dl_setting var="mb_scale_gain" min="2.0e-3" step="1e-4" max="2.5e-3" module="mb_scale"/>
|
||||
<dl_setting var="mb_scale_calib" min="0" step="1" max="1" module="mb_scale" handler="Calib"/>
|
||||
</dl_settings>
|
||||
|
||||
|
||||
|
||||
|
||||
</dl_settings>
|
||||
</settings>
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
<settings>
|
||||
<dl_settings>
|
||||
<!-- <dl_setting var="pt_ant_mode" min="0" step="1" max="3" handler="SetMode"/> -->
|
||||
<dl_setting var="pt_ant_motors_y_power" min="-1" step="0.1" max="1" module="pt_ant_motors" handler="SetYPower"/>
|
||||
<dl_setting var="pt_ant_motors_z_power" min="-1" step="0.1" max="1" module="pt_ant_motors" handler="SetZPower"/>
|
||||
<dl_setting shortname="power y" var="pt_ant_motors_y_power" min="-1" step="0.1" max="1" module="pt_ant_motors" handler="SetYPower"/>
|
||||
<dl_setting shortname="power z" var="pt_ant_motors_z_power" min="-1" step="0.1" max="1" module="pt_ant_motors" handler="SetZPower"/>
|
||||
</dl_settings>
|
||||
</settings>
|
||||
|
||||
@@ -3,8 +3,8 @@
|
||||
<settings>
|
||||
<dl_settings>
|
||||
|
||||
<dl_settings NAME="Analog Baro">
|
||||
<dl_setting var="booz2_analog_baro_offset" min="1" step="1" max="1022" module="booz2_analog_baro" handler="SetOffset" shortname="offset"/>
|
||||
<dl_settings NAME="Misc">
|
||||
<dl_setting var="telemetry_mode_Main" min="0" step="1" max="7" module="booz2_telemetry" shortname="telemetry mode"/>
|
||||
</dl_settings>
|
||||
|
||||
<dl_settings NAME="Rate Loop">
|
||||
@@ -30,7 +30,8 @@
|
||||
<dl_setting var="booz2_guidance_v_kp" min="-400" step="1" max="0" module="booz2_guidance_v" shortname="kp"/>
|
||||
<dl_setting var="booz2_guidance_v_kd" min="-400" step="1" max="0" module="booz2_guidance_v" shortname="kd"/>
|
||||
<dl_setting var="booz2_guidance_v_ki" min="-400" step="1" max="0" module="booz2_guidance_v" shortname="ki"/>
|
||||
</dl_settings>
|
||||
<dl_setting var="booz2_guidance_v_z_sp" min="50" step="1" max="950" module="booz2_guidance_v" shortname="sp"/>
|
||||
</dl_settings>
|
||||
|
||||
|
||||
<dl_settings NAME="Filter">
|
||||
@@ -38,8 +39,8 @@
|
||||
</dl_settings>
|
||||
|
||||
|
||||
<dl_settings NAME="Misc">
|
||||
<dl_setting var="telemetry_mode_Main" min="0" step="1" max="6" module="booz2_telemetry" shortname="telemetry mode"/>
|
||||
<dl_settings NAME="Analog Baro">
|
||||
<dl_setting var="booz2_analog_baro_offset" min="1" step="1" max="1022" module="booz2_analog_baro" handler="SetOffset" shortname="offset"/>
|
||||
</dl_settings>
|
||||
|
||||
|
||||
|
||||
+10
-10
@@ -7,14 +7,14 @@
|
||||
<mode name="default">
|
||||
<message name="ALIVE" period="5."/>
|
||||
<message name="BOOZ_STATUS" period=".5"/>
|
||||
<message name="RC" period="0.5"/>
|
||||
<!-- <message name="RC" period="0.5"/> -->
|
||||
<!-- <message name="BOOZ_FD" period="0.05"/> -->
|
||||
<!-- <message name="BOOZ_DEBUG" period="0.25"/> -->
|
||||
<message name="ACTUATORS" period="0.5"/>
|
||||
<message name="BOOZ_HOV_LOOP" period="0.05"/>
|
||||
<message name="BOOZ_VERT_LOOP" period="0.05"/>
|
||||
<message name="BOOZ_CONTROL" period="0.025"/>
|
||||
<message name="BOOZ_CMDS" period="0.025"/>
|
||||
<!-- <message name="BOOZ_HOV_LOOP" period="0.05"/> -->
|
||||
<!-- <message name="BOOZ_VERT_LOOP" period="0.05"/> -->
|
||||
<!-- <message name="BOOZ_CONTROL" period="0.025"/> -->
|
||||
<!-- <message name="BOOZ_CMDS" period="0.025"/> -->
|
||||
<!-- <message name="BOOZ_UF_RATES" period="0.05"/> -->
|
||||
<message name="DL_VALUE" period="1."/>
|
||||
</mode>
|
||||
@@ -29,13 +29,13 @@
|
||||
|
||||
<mode name="default">
|
||||
<!-- <message name="IMU_GYRO_LP" period=".017"/> -->
|
||||
<message name="AHRS_STATE" period=".1"/>
|
||||
<message name="AHRS_COV" period=".2"/>
|
||||
<message name="AHRS_MEASURE" period=".1"/>
|
||||
<message name="AHRS_STATE" period=".5"/>
|
||||
<message name="AHRS_COV" period=".5"/>
|
||||
<message name="AHRS_MEASURE" period=".5"/>
|
||||
<!-- <message name="IMU_ACCEL_RAW" period=".02"/> -->
|
||||
<message name="IMU_ACCEL" period=".1"/>
|
||||
<message name="IMU_ACCEL" period=".5"/>
|
||||
<!-- <message name="IMU_GYRO_RAW" period=".05"/> -->
|
||||
<message name="IMU_GYRO" period=".1"/>
|
||||
<message name="IMU_GYRO" period=".5"/>
|
||||
<!-- <message name="IMU_MAG_RAW" period=".05"/>
|
||||
<message name="IMU_MAG" period=".5"/>
|
||||
<message name="IMU_PRESSURE" period=".5"/>
|
||||
|
||||
@@ -4,29 +4,11 @@
|
||||
|
||||
|
||||
<process name="Main">
|
||||
|
||||
<mode name="default">
|
||||
<message name="DL_VALUE" period="1.1"/>
|
||||
<message name="BOOZ_STATUS" period="1.2"/>
|
||||
|
||||
<!-- <message name="BOOZ2_RATE_LOOP" period=".05"/> -->
|
||||
<!-- <message name="BOOZ2_STAB_ATTITUDE" period=".05"/> -->
|
||||
<!-- <message name="BOOZ2_CMD" period=".05"/> -->
|
||||
<!-- <message name="BOOZ2_STAB_ATTITUDE_REF" period=".05"/> -->
|
||||
<!-- <message name="BOOZ2_ALIGNER" period=".1"/> -->
|
||||
<!-- <message name="BOOZ2_FILTER" period=".1"/> -->
|
||||
<!-- <message name="BOOZ2_FILTER_Q" period=".1"/> -->
|
||||
<!-- <message name="BOOZ2_GUIDANCE" period=".25"/> -->
|
||||
|
||||
<message name="BOOZ2_GYRO" period=".075"/>
|
||||
<message name="BOOZ2_ACCEL" period=".075"/>
|
||||
<message name="BOOZ2_MAG" period=".1"/>
|
||||
|
||||
<!-- <message name="IMU_ACCEL_RAW" period=".05"/> -->
|
||||
<!-- <message name="IMU_GYRO_RAW" period=".1"/> -->
|
||||
<!-- <message name="IMU_MAG_RAW" period=".05"/> -->
|
||||
|
||||
<!-- <message name="BOOZ2_FILTER_COR" period=".05"/> -->
|
||||
<!-- <message name="BOOZ2_ATT_LOOP" period=".05"/> -->
|
||||
<message name="BOOZ2_FP" period="0.25"/>
|
||||
<message name="ALIVE" period="2.1"/>
|
||||
</mode>
|
||||
|
||||
@@ -63,7 +45,6 @@
|
||||
<message name="BOOZ2_RATE_LOOP" period=".02"/>
|
||||
</mode>
|
||||
|
||||
|
||||
<mode name="attitude_loop">
|
||||
<message name="BOOZ_STATUS" period="1.2"/>
|
||||
<message name="DL_VALUE" period="0.5"/>
|
||||
@@ -79,6 +60,9 @@
|
||||
<message name="BOOZ2_VERT_LOOP" period=".02"/>
|
||||
</mode>
|
||||
|
||||
<mode name="h_loop">
|
||||
<message name="BOOZ2_HOVER_LOOP" period="0.25"/>
|
||||
</mode>
|
||||
|
||||
|
||||
</process>
|
||||
|
||||
@@ -7,8 +7,8 @@
|
||||
#include "mb_tacho.h"
|
||||
#include "mb_servo.h"
|
||||
#include "i2c.h"
|
||||
//#include "mb_twi_controller_asctech.h"
|
||||
#include "mb_twi_controller_mkk.h"
|
||||
#include "mb_twi_controller_asctech.h"
|
||||
//#include "mb_twi_controller_mkk.h"
|
||||
#include "mb_current.h"
|
||||
#include "mb_scale.h"
|
||||
|
||||
|
||||
@@ -7,6 +7,8 @@
|
||||
#include <Ivy/ivy.h>
|
||||
#include <Ivy/ivyglibloop.h>
|
||||
|
||||
#define ASTECH 1
|
||||
|
||||
#include "tuning.h"
|
||||
|
||||
//#include "sliding_plot.h"
|
||||
@@ -16,6 +18,8 @@
|
||||
#define MB_MODES_RAMP 2
|
||||
#define MB_MODES_STEP 3
|
||||
#define MB_MODES_PRBS 4
|
||||
#define MB_MODES_SINE 5
|
||||
#define MB_MODES_FIXED_RPM 6
|
||||
|
||||
#define AS_MOT_FRONT 0
|
||||
#define AS_MOT_BACK 1
|
||||
@@ -39,7 +43,12 @@ struct motor_bench_state {
|
||||
double amps;
|
||||
double thrust;
|
||||
double torque;
|
||||
double av_rpm;
|
||||
double av_throttle;
|
||||
double av_thrust;
|
||||
double av_amps;
|
||||
GIOChannel* log_channel;
|
||||
GIOChannel* log_channel_static;
|
||||
};
|
||||
|
||||
struct motor_bench_gui {
|
||||
@@ -111,6 +120,24 @@ static void on_MOTOR_BENCH_STATUS(IvyClientPtr app, void *user_data, int argc, c
|
||||
// g_message("foo %f %f %f %f %d", mb_state.time, throttle, rpm, amp, mode);
|
||||
}
|
||||
|
||||
static void on_MOTOR_BENCH_STATIC(IvyClientPtr app, void *user_data, int argc, char *argv[]){
|
||||
mb_state.av_rpm = atof(argv[0]);
|
||||
mb_state.av_thrust = atof(argv[1]);
|
||||
mb_state.av_amps = atof(argv[2]);
|
||||
mb_state.av_throttle = atof(argv[3]);
|
||||
|
||||
if (mb_state.log_channel_static) {
|
||||
GString* str = g_string_sized_new(256);
|
||||
g_string_printf(str, "%0f %.3f %.2f %.1f\n", mb_state.av_throttle, mb_state.av_rpm, mb_state.av_amps, mb_state.av_thrust);
|
||||
gsize b_writen;
|
||||
GError* my_err = NULL;
|
||||
GIOStatus stat = g_io_channel_write_chars(mb_state.log_channel_static,str->str, str->len, &b_writen, &my_err);
|
||||
g_string_free(str, TRUE);
|
||||
}
|
||||
g_message("in_static %f %f %f %f", mb_state.av_throttle, mb_state.av_rpm, mb_state.av_amps, mb_state.av_thrust);
|
||||
}
|
||||
|
||||
|
||||
static gboolean timeout_callback(gpointer data) {
|
||||
GString* str = g_string_sized_new(64);
|
||||
g_string_printf(str, "%.2f s", mb_state.time);
|
||||
@@ -135,31 +162,43 @@ static void on_log_button_toggled (GtkWidget *widget, gpointer data) {
|
||||
const gchar *log_file_name = gtk_entry_get_text (GTK_ENTRY (mb_gui.entry_log));
|
||||
GError* my_err = NULL;
|
||||
mb_state.log_channel = g_io_channel_new_file (log_file_name, "w", &my_err);
|
||||
GString* static_name = g_string_sized_new(128);
|
||||
g_string_printf(static_name,"%s%s", log_file_name, "_static");
|
||||
mb_state.log_channel_static = g_io_channel_new_file (static_name->str, "w", &my_err);
|
||||
g_string_free(static_name, TRUE);
|
||||
}
|
||||
else {
|
||||
gtk_editable_set_editable( GTK_EDITABLE(mb_gui.entry_log), TRUE );
|
||||
if (mb_state.log_channel) {
|
||||
g_io_channel_close(mb_state.log_channel);
|
||||
g_io_channel_close(mb_state.log_channel_static);
|
||||
mb_state.log_channel = NULL;
|
||||
mb_state.log_channel_static = NULL;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static void on_as_test_button_clicked (GtkWidget *widget, gpointer data) {
|
||||
#ifdef ASTECH
|
||||
IvySendMsg("dl DL_SETTING %d %d %d", mb_id, PPRZ_MB_TWI_CONTROLLER_ASCTECH_COMMAND_TYPE, AS_CMD_TEST_ADDR);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void on_as_reverse_button_clicked (GtkWidget *widget, gpointer data) {
|
||||
#ifdef ASTECH
|
||||
IvySendMsg("dl DL_SETTING %d %d %d", mb_id, PPRZ_MB_TWI_CONTROLLER_ASCTECH_COMMAND_TYPE, AS_CMD_REVERSE);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
static void on_as_addr_changed (GtkRadioButton *radiobutton, gpointer user_data) {
|
||||
#ifdef ASTECH
|
||||
if (!gtk_toggle_button_get_active(GTK_TOGGLE_BUTTON(radiobutton)))
|
||||
return;
|
||||
guint new_addr = (guint)user_data;
|
||||
IvySendMsg("dl DL_SETTING %d %d %d", mb_id, PPRZ_MB_TWI_CONTROLLER_ASCTECH_ADDR, new_addr);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@@ -175,6 +214,7 @@ int main (int argc, char** argv) {
|
||||
|
||||
IvyInit ("MotorBench", "MotorBench READY", NULL, NULL, NULL, NULL);
|
||||
IvyBindMsg(on_MOTOR_BENCH_STATUS, NULL, "^\\S* MOTOR_BENCH_STATUS (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)");
|
||||
IvyBindMsg(on_MOTOR_BENCH_STATIC, NULL, "^\\S* MOTOR_BENCH_STATIC (\\S*) (\\S*) (\\S*) (\\S*)");
|
||||
IvyStart("127.255.255.255");
|
||||
|
||||
g_timeout_add(40, timeout_callback, NULL);
|
||||
@@ -232,12 +272,24 @@ static GtkWidget* build_gui ( void ) {
|
||||
gtk_box_pack_start (GTK_BOX (vbox2), rb_prbs, TRUE, TRUE, 0);
|
||||
gtk_radio_button_set_group (GTK_RADIO_BUTTON (rb_prbs), rb_mode_group);
|
||||
rb_mode_group = gtk_radio_button_get_group (GTK_RADIO_BUTTON (rb_prbs));
|
||||
GtkWidget* rb_sine = gtk_radio_button_new_with_mnemonic (NULL, "sine");
|
||||
gtk_box_pack_start (GTK_BOX (vbox2), rb_sine, TRUE, TRUE, 0);
|
||||
gtk_radio_button_set_group (GTK_RADIO_BUTTON (rb_sine), rb_mode_group);
|
||||
rb_mode_group = gtk_radio_button_get_group (GTK_RADIO_BUTTON (rb_sine));
|
||||
GtkWidget* rb_fixed_rpm = gtk_radio_button_new_with_mnemonic (NULL, "fixed");
|
||||
gtk_box_pack_start (GTK_BOX (vbox2), rb_fixed_rpm, TRUE, TRUE, 0);
|
||||
gtk_radio_button_set_group (GTK_RADIO_BUTTON (rb_fixed_rpm), rb_mode_group);
|
||||
rb_mode_group = gtk_radio_button_get_group (GTK_RADIO_BUTTON (rb_fixed_rpm));
|
||||
|
||||
|
||||
|
||||
g_signal_connect ((gpointer) rb_idle, "toggled", G_CALLBACK (on_mode_changed), (gpointer)MB_MODES_IDLE);
|
||||
g_signal_connect ((gpointer) rb_manual, "toggled", G_CALLBACK (on_mode_changed), (gpointer)MB_MODES_MANUAL);
|
||||
g_signal_connect ((gpointer) rb_ramp, "toggled", G_CALLBACK (on_mode_changed), (gpointer)MB_MODES_RAMP);
|
||||
g_signal_connect ((gpointer) rb_step, "toggled", G_CALLBACK (on_mode_changed), (gpointer)MB_MODES_STEP);
|
||||
g_signal_connect ((gpointer) rb_prbs, "toggled", G_CALLBACK (on_mode_changed), (gpointer)MB_MODES_PRBS);
|
||||
g_signal_connect ((gpointer) rb_sine, "toggled", G_CALLBACK (on_mode_changed), (gpointer)MB_MODES_SINE);
|
||||
g_signal_connect ((gpointer) rb_fixed_rpm, "toggled", G_CALLBACK (on_mode_changed), (gpointer)MB_MODES_FIXED_RPM);
|
||||
|
||||
|
||||
//
|
||||
|
||||
@@ -5,12 +5,12 @@ getf('mb_utils.sci');
|
||||
args = sciargs();
|
||||
[nb_args, foo] = size(args)
|
||||
filename = args(nb_args);
|
||||
filename = "data/steps2_stout_aero_geared.txt"
|
||||
filename = "asctech/log_ramp_crooked_prop.txt"
|
||||
|
||||
[time, throttle, rpm, amp, thrust, torque] = read_mb_log(filename);
|
||||
|
||||
|
||||
f_sample = 200.;
|
||||
f_sample = 250.;
|
||||
fc = 100.;
|
||||
f_rpm = low_pass_filter(f_sample, fc, rpm);
|
||||
|
||||
@@ -28,3 +28,5 @@ subplot(3,1,3)
|
||||
xtitle('Filtered Rpm');
|
||||
plot2d(time, f_rpm);
|
||||
//plot2d(rpm, throttle);
|
||||
|
||||
save('asctech/log_ramp_crooked_prop.dat', time, throttle, rpm, amp, thrust, torque);
|
||||
Reference in New Issue
Block a user