thank you for your response… i will prepare a cable so i can use a second can node coz on my fc I’ve only one CAN port.
Good day, would you mind advice me pls for the correct firmware file for update the Kitcan Node by mro… there is also a param i can use to enable/disable the arm switch of the node in MP?
Waiting for a kind response
Hi Dave. There is currently no param to enable / disable the arm switch. It is an option that gets built into the firmware.
Here is a link to the latest mRo m10025 firmware. https://github.com/mRoboticsIO/Firmware/tree/master/M10025_KITCAN . Please let me know if you need any assistance.
I’m working through some challenges getting a custom node to load with AP_Periph bootloader. I think I have all the steps in place including watchdog pat but appear to be getting an IWDG reset with an error code 15 in UAVCAN GUI.
I see that there are provisions for printf debugging messages (e.g. https://github.com/ArduPilot/ardupilot/blob/master/Tools/AP_Bootloader/can.cpp#L578). Are these enabled by default in f103-GPS_bl or do they need a compile switch and rebuild? Also how to tell USARTn and pins?
Best Regards,
George
I’m still trying to get debug info from AP_Periph bootloader running on a F103 based platform.
I see printf() statements sprinked throughout the bootloader code example:
And it appears to be directed to SD1 (which I assume to be STM32 USART1?)
From auto-generated hwdef.h in the build folder USART1 TX/RX appears to be on PA9/PA10, but I’m not getting any output there.
I’m missing something, just not sure what or where to look. Any breadcumbs would be most welcomed.
Given error code 15 most likely the board is locking up. The way I would normally debug this sort of issue is to either use a debugger or use GPIO toggles.
Assuming you don’t have a debugger setup for this board then GPIO toggles are the way to go. These are the most reliable way to get a small amount of information out. The aim of the GPIO toggles is to narrow down where you are getting to in the startup code.
What you do is setup a GPIO output pin in hwdef.dat then use palToggleLine() to toggle the pin between high and low a distinctive number of times, watching with a logic analyser (eg. Saleae) to see what is happening.
This sort of GPIO toggle can be used very early in the startup, before serial ports are initialised.
For a fancy version of this which writes strings see this code:
you don’t really need anything so fancy for this debugging. You’re just trying to narrow down what section of setup() or loop() you are getting to.
It does assume you have a logic analyser though. If you don’t have one then get one, as it really is an essential tool for board bringup.
Also, post a link to your hwdef.dat in case there is something easy to spot in it.
Cheers, Tridge
Thanks for the guidance. I have a Segger J-Link debugger and Saleae logic probe available. I’ll give the GPIO toggle a try.
Best Regards,
George
Any hints on how to set up a rangefinder with the mRo CAN node? I have tried an LidarLitev3 on i2c and an SF11C on i2c and serial connection using the latest f303-Universal firmware. I don’t see any rangefinder messages when inspecting the bus using the UAVCAN GUI tool. I’ve set the AP_Periph parameters RNGFND1_* parameters and verified they work correctly with either device directly connected to Cube Orange.
In the case of serial connection I’m connecting to the GPS port on the mRo node and I’ve also tried setting GPS_TYPE to 0. I have no problems with an i2c airspeed sensor over via the same CAN node.
Good day, on MP just set 24 as rangefinder type…
Hi David, thanks for the reply, still not working for me. I’m not seeing rangefinder measurement UAVCAN messages in UAVCAN GUI tool, making me think the issue is on the CAN node side.
AP_Periph parameters:
0 FORMAT_VERSION integer 2
1 CAN_NODE integer 0
2 CAN_BAUDRATE integer 1000000
3 FLASH_BOOTLOADER integer 0
4 GPS_TYPE integer 0
5 GPS_NAVFILTER integer 8
6 GPS_MIN_DGPS integer 100
7 GPS_SBAS_MODE integer 2
8 GPS_MIN_ELEV integer -100
9 GPS_INJECT_TO integer 127
10 GPS_SBP_LOGMASK integer -256
11 GPS_RAW_DATA integer 0
12 GPS_GNSS_MODE integer 0
13 GPS_SAVE_CFG integer 2
14 GPS_AUTO_CONFIG integer 1
15 GPS_RATE_MS integer 200
16 GPS_POS1_X real 0.0
17 GPS_POS1_Y real 0.0
18 GPS_POS1_Z real 0.0
19 GPS_DELAY_MS integer 0
20 COMPASS_OFS_X real 0.0
21 COMPASS_OFS_Y real 0.0
22 COMPASS_OFS_Z real 0.0
23 COMPASS_DEC real 0.0
24 COMPASS_LEARN integer 0
25 COMPASS_USE integer 1
26 COMPASS_AUTODEC integer 1
27 COMPASS_MOTCT integer 0
28 COMPASS_MOT_X real 0.0
29 COMPASS_MOT_Y real 0.0
30 COMPASS_MOT_Z real 0.0
31 COMPASS_ORIENT integer 0
32 COMPASS_EXTERNAL integer 0
33 COMPASS_DEV_ID integer 0
34 COMPASS_DIA_X real 0.0
35 COMPASS_DIA_Y real 0.0
36 COMPASS_DIA_Z real 0.0
37 COMPASS_ODI_X real 0.0
38 COMPASS_ODI_Y real 0.0
39 COMPASS_ODI_Z real 0.0
40 COMPASS_CAL_FIT real 16.0
41 COMPASS_OFFS_MAX integer 1800
42 COMPASS_TYPEMASK integer 0
43 COMPASS_FLTR_RNG integer 0
44 COMPASS_AUTO_ROT integer 2
45 COMPASS_PRIO1_ID integer 0
46 COMPASS_ENABLE integer 1
47 COMPASS_SCALE real 0.0
48 COMPASS_OPTIONS integer 0
49 BARO_ABS_PRESS real 0.0
50 BARO_TEMP real 0.0
51 BARO_ALT_OFFSET real 0.0
52 BARO_PRIMARY integer 0
53 BARO_EXT_BUS integer -1
54 BARO_ABS_PRESS2 real 0.0
55 BARO_ABS_PRESS3 real 0.0
56 BARO_FLTR_RNG integer 0
57 BARO_PROBE_EXT integer 0
58 BARO_ENABLE integer 1
59 LED_BRIGHTNESS integer 100
60 ARSP_TYPE integer 1
61 ARSP_TUBE_ORDER integer 2
62 ARSP_PSI_RANGE real 1.0
63 RNGFND_BAUDRATE integer 115200
64 RNGFND1_TYPE integer 8
65 RNGFND1_PIN integer -1
66 RNGFND1_SCALING real 1.0
67 RNGFND1_OFFSET real 0.0
68 RNGFND1_FUNCTION integer 0
69 RNGFND1_MIN_CM integer 20
70 RNGFND1_MAX_CM integer 12000
71 RNGFND1_STOP_PIN integer -1
72 RNGFND1_RMETRIC integer 1
73 RNGFND1_PWRRNG integer 0
74 RNGFND1_GNDCLEAR integer 10
75 RNGFND1_ADDR integer 102
76 RNGFND1_POS_X real 0.0
77 RNGFND1_POS_Y real 0.0
78 RNGFND1_POS_Z real 0.0
79 RNGFND1_ORIENT integer 25
80 ADSB_BAUDRATE integer 0 '
UAVCAN traffic:
Sam
which rangefinder are you using?
The above is SF11/C. I’ve also tried LidarLite v3. Both work fine attached directly to Cube.
Are you guys running on the F103 or F303 node?
Hi Phillip, this is the F303, the sikscreen says “mRo CAN node v1”.
Great, are the range finders that are not working all connected via I2C?
I’ve tried the LidarLite v3 on i2c and the SF11/C on both i2c and serial - with the appropriate changes to RNGFND1_TYPE on the CAN node.
I’ll look into this and get back to you. Typically we need to tell APPeriph to look for I2C devices like this:
and support all external compass and baro types
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_PROBE_EXTERNAL_I2C_BAROS
I need to see if that is required for Range Finders, Give me an hour or 2 to get to a computer.
Thanks, appreciate it.
Samuel, I don’t see anything obviously wrong but I will bring it up with Tridge.
Matt, I’ll email you a binary to test for ERB support.
Thanks Philip. If it helps I’m sure I could loan you a rangefinder to test with.