New message and variables in APM Planner 2

As a clarification, using mavproxy is just a quicker way of testing that the message itself is being sent correctly. I did this because when I edited the APM Planner code, I had a bit of trouble getting it to display the message, although the rest of APM Planner was working. So I didn’t know if my edits to APM Planner were not working, or if the message in the Ardupilot code itself was not working. It is much easier to test this with mavproxy than APM Planner.

I would like to point out, that I want to send my message from vehicle code, not in common.py - or is that needed? (Editing of common.py if I am already sending that message from ardupilot code).

The messages are all sent from the vehicle code. Mavproxy is just a simpler way than APM Planner to test that the vehicle code is sending the message correctly. So editing common.py will not send the message, but rather just receive it from the vehicle and allow you to check that it is sending correctly. (I understand that you know this already, I’m just adding this information to clarify for anyone else who happens to be doing this same thing.)

I know that is not the best way to answer few months after but this topic was really helpful for me and I would like to add few details for people who would like to make it works with Mission Planner and SITL rather than a real drone. Hope it could help some people (I adapt the description of @eMrazSVK to give the full steps).

ArduPilot side:

  • Edit /ardupilot/modules/mavlink/message_definitions/v1.0/common.xml by adding your message
  • Build whole project
  • Create your appropriate function in ArduPilot as explain in the other topic
  • Different from this topic. Generate ardupilotmega.py file with mavgenerate.py also located in ardupilot/modules/mavlink/, it will open GUI, the input is message_definitions/ardupilotmega.xml and for the output create a new file called ardupilotmega.py (command to launch mavgenerate python mavgenerate.py)
  • Copy ardupilot/modules/mavlink/ardupilotmega.py to /usr/local/lib/python2.7/dist-packages/pymavlink/dialects/v10/.
  • Run sim_vehicle.py. Ardupilot use by default this dialect (ardupilotmega v10) if no special parameters has been added so if you replaced the file it should find your message. If you followed the instructions of last messages it can also works by adding --mavproxy-args "--dialect common" parameters when you run sim_vehicle.py. If you still have error with BAD_DATA, you may try to copy /ardupilot/modules/mavlink/message_definitions/v1.0/common.xml to /usr/local/lib/python2.7/dist-packages/pymavlink/message_definitions/v1.0/ I did it, but not sure if it is necessary
  • check with status command in MAVProxy console if you can see your message ID and the value you setted. You can also display in real time your data with module load graph and graph YOUR_MSG_ID.NAME_VARIABLE. If it’s working, go to MP side!

Mission Planner side:

  • Follow the instruction to install mission planner
  • Modify the file MissionPlanner\ExtLibs\Mavlink\message_definitions\common.xml with your new message (has to be the same than ArduPilot side)
  • Install python 2.7 for Windows and run MissionPlanner\ExtLibs\Mavlink\regenerate.bat from Windows and not cygwin or cmd prompt. Make sure you added the C:\Python27 to your PATH before. It will generate a new Mavlink.cs with your message ID
  • Build and run MP. A good way to check if your message is received, press ctrl+F in MP and click “MAV Link” button and see if your message is there.

Done !

1 Like

@Katawan I am really glad it helped you!
I am planning to write a tutorial for programming communication protocol via UART for ArduPilot, it should contain this topic too. But I need to do pull request first and be 100% sure that all I’ve done is working.

1 Like