Closed shlapion closed 6 years ago
It should not be necessary to define USE_RX_MSP
in the target header file, it is already defined in common.h
.
You need to provide more of a traceback for us to see why your compilation fails.
Thank you for the reply @stronnag .
Indeed it is defined in the common.h
. However...
Long story short, I am trying to use ROS to send MSP commands to the FC. More specifically I am trying to send RC data using a ROS node. To get the FC to process the data sent I am using the MSP_SET_RAW_RC
function. The messages are accepted but not processed.
After digging around, I found a thread in which someone pointed out that USE_RX_MSP
has to be enabled for the FC to process the message. So I thought it might be worth a try, and compile my own firmware.
What exactly could I provide to shed some light on the compilation error? For starters the terminal output attached below
make TARGET=MATEKF722
%% target.c
%% main.c
%% common_hardware.c
%% assert.c
%% build_config.c
%% debug.c
%% memory.c
%% printf.c
%% time.c
%% config_eeprom.c
%% config_streamer.c
%% feature.c
%% parameter_group.c
%% adc.c
%% bus.c
%% bus_busdev_i2c.c
%% bus_busdev_spi.c
%% bus_i2c_soft.c
%% display.c
%% exti.c
%% gps_i2cnav.c
%% io.c
%% io_pca9685.c
%% light_led.c
%% logging.c
%% rx_nrf24l01.c
%% rx_spi.c
%% pitotmeter_adc.c
%% pwm_esc_detect.c
%% pwm_mapping.c
%% pwm_output.c
%% rcc.c
%% rx_pwm.c
%% serial.c
%% sound_beeper.c
%% stack_check.c
%% system.c
%% timer.c
%% lights_io.c
%% cli.c
%% config.c
%% controlrate_profile.c
%% fc_core.c
%% fc_init.c
%% fc_tasks.c
%% fc_hardfaults.c
%% fc_msp.c
%% fc_msp_box.c
%% rc_adjustments.c
%% rc_controls.c
%% rc_curves.c
%% rc_modes.c
%% runtime_config.c
%% settings.c
%% stats.c
%% failsafe.c
%% hil.c
%% imu.c
./src/main/flight/imu.c: In function 'imuMahonyAHRSupdate':
./src/main/flight/imu.c:266:5: warning: missing braces around initializer [-Wmissing-braces]
STATIC_FASTRAM fpVector3_t vGyroDriftEstimate = { 0 };
^
./src/main/flight/imu.c:266:5: warning: (near initialization for 'vGyroDriftEstimate.v') [-Wmissing-braces]
%% mixer.c
%% pid.c
%% pid_autotune.c
%% rth_estimator.c
%% servos.c
%% wind_estimator.c
%% beeper.c
%% lights.c
%% pwmdriver_i2c.c
%% serial.c
%% serial_4way.c
%% serial_4way_avrootloader.c
%% serial_4way_stk500v2.c
%% statusindicator.c
%% rcdevice.c
%% rcdevice_cam.c
%% msp_serial.c
%% fport.c
%% ibus.c
%% jetiexbus.c
%% msp.c
%% uib_rx.c
%% nrf24_cx10.c
%% nrf24_inav.c
%% nrf24_h8_3d.c
%% nrf24_syma.c
%% nrf24_v202.c
%% pwm.c
%% rx.c
%% rx_spi.c
%% crsf.c
%% sbus.c
%% sbus_channels.c
%% spektrum.c
%% sumd.c
%% sumh.c
%% xbus.c
%% eleres.c
%% scheduler.c
%% acceleration.c
%% battery.c
%% temperature.c
%% boardalignment.c
%% compass.c
./src/main/sensors/compass.c: In function 'compassInit':
./src/main/sensors/compass.c:312:14: warning: missing initializer for field 'pitch' of 'fp_angles_def' [-Wmissing-field-initializers]
.angles.pitch = DECIDEGREES_TO_RADIANS(compassConfig()->pitchDeciDegrees),
^
In file included from ./src/main/sensors/compass.c:26:0:
./src/main/common/maths.h:87:11: note: 'pitch' declared here
float pitch;
^
./src/main/sensors/compass.c:313:14: warning: missing initializer for field 'yaw' of 'fp_angles_def' [-Wmissing-field-initializers]
.angles.yaw = DECIDEGREES_TO_RADIANS(compassConfig()->yawDeciDegrees),
^
In file included from ./src/main/sensors/compass.c:26:0:
./src/main/common/maths.h:88:11: note: 'yaw' declared here
float yaw;
^
./src/main/sensors/compass.c: In function 'compassUpdate':
./src/main/sensors/compass.c:416:13: warning: missing initializer for field 'y' of 'struct
What version of GCC are you using? I suspect your compiler is too old. RX_MSP works when I last tested it, probably a month or two ago.
I am using version 5.4.0. I updated to version 6.5.0 and made it the default compiler. Ran make again, facing the same issue.
On which version of iNav did you test RX_MSP?
6.5 is probably too old, please use 7.3 or 8.2
I've tested RX_MSP on probably every version of iNav. There was one in the distant past where it was broken. You could search the closed issues if it's of historic importance.
And it works fine with the current development branch, as expected.
Updated to 8.1 still facing the same issue.
Also dug around the closed issues section. In #1910 you posted a picture of test you performed. Would it be possible to re-upload the test file and a short instruction of how to perform the test.
Is there a way to see if RX_MSP
is enabled?
Output of CLI diff
below:
diff
feature GPS feature BLACKBOX feature PWM_OUTPUT_ENABLE
serial 3 2 115200 38400 0 115200
aux 0 0 0 1300 1700 aux 1 1 12 1600 2100 aux 2 3 5 1000 1200 aux 3 9 5 1000 1200 aux 4 8 13 1800 2100 aux 5 19 3 1000 1200 aux 6 17 0 1300 1700
set acc_hardware = MPU6500 set acczero_x = -9 set acczero_y = -41 set acczero_z = -1 set accgain_x = 4086 set accgain_y = 4087 set accgain_z = 4094 set align_mag = CW90FLIP set mag_hardware = HMC5883 set mag_declination = 250 set magzero_x = -47 set magzero_y = -67 set magzero_z = -151 set baro_hardware = BMP280 set pitot_hardware = NONE set motor_pwm_rate = 2000 set motor_pwm_protocol = MULTISHOT set failsafe_procedure = DROP set vbat_max_cell_voltage = 420 set gps_sbas_mode = AUTO set nav_extra_arming_safety = OFF set nav_auto_speed = 2000
profile 1
set mc_p_pitch = 37 set mc_i_pitch = 27 set mc_d_pitch = 21 set mc_p_roll = 37 set mc_i_roll = 27 set mc_d_roll = 21 set roll_rate = 35 set pitch_rate = 35 set yaw_rate = 25
feature RX_MSP
set receiver_type = MSP
save
Tested by:
./msp_set_rc.rb /dev/ttyuSB0
i.e. a separate UART enabled for MSP, in this case via a 3DR radio, but a USB/TTY connection would work.You should then see the configurator bars bounce around and something like:
Tx: 1555,1501,1501,1505,1017,1442,1663,1969
Rx: 1501,1505,1501,1555,1017,1442,1663,1969
Tx: 1558,1551,1563,1527,1017,1442,1663,1969
Rx: 1551,1527,1563,1558,1017,1442,1663,1969
The reason why the RX values differ in order from the TX values is that this model is set to TAER and I forgot to change it.
Note also that the whole thing is monstrously inefficient (just a POC) and you may need to fiddle around with the sleep
s .
Many thanks ! Will look test it out tommorow first thing in the morning, sitting in a lecture at the moment.
Have fun. In my experience while RX_MSP seems to work as long as you don't stupidly issue stick commands in rapid succession.
@shlapion It would be awesome it you could test my MSP_RX python code on your setup. I confirmed it to work on iNav 2.0 on omnibus f4 pro v3 and SP racing F3. The code is here : https://github.com/nik012003/OpenGS Inside Protocol_handler there is a jupyter notebook with some tests, including set_raw_rc via MSP v2. Thank you in advanced.
@nik012003 thank you for the insight and sorry for the late reply. Was away for a couple of weeks. Will keep you posted with the results.
@nik012003 being new to Python I am not really sure how to run your example inside the Protocol_handler, so I wrote my own script.
I have managed to read the sensor data(attitude
,raw_gps
,raw_imu
) works wonderfully.
Setting the RC values using the set_raw_rc
function works however the copter does not arm. (The values for the channels have been stored while the copter was armed and then passed to the set_raw_rc
as arguments)
Using the get_rc
function I have the same values as set with the set_raw_rc
function so I'm guessing it works.
I have enabled the feature RX_MSP
and set the receiver_type = MSP
as @stronnag suggested.
Am I missing something?
Thank you for the support!
@shlapion I think you should enable motor control in the Motor part of the configurator to do so. It is a safety feature which disables arming when the configurator is running. If you have any problems feel free to contact me on hangouts or skype so we can better understend the problem and fix it faster.
@nik012003 thank you for the quick reply. I have enabled the motor control in iNav. Sadly still no result. Would be great if we could take this conversation forward on hangouts or skype. Whichever works for you better. You can drop me a mail/message on google at the same username as here.
@shlapion I've added you on skype.
I have managed to read the sensor data(
attitude
,raw_gps
,raw_imu
) works wonderfully. Setting the RC values using theset_raw_rc
function works however the copter does not arm.
Arming and disarming via RX_MSP work as expected. Just make sure there is nothing blocking arming and you have the right channel map.
Have gotten it to work. The rate at which the MSP messages were sent was the issue. @stronnag thank you for the support. For anyone else trying to make this work, will clean up the code and share it.
Greeting,
I am trying to enable the
USE_RX_MSP
feature for my Matek F722 FC. In order to to this I have tried to build my own custom firmware by adding#define USE_RX_MSP
to the target.h file of the board.However when I try to compile I get the following error:
Makefile:341: recipe for target 'obj/main/MATEKF722/cms/cms_menu_battery.o' failed
Any help is greatly appreciated !