I’m just getting started on a project where I want to make humidity/and temp measurements at various altitudes. I’ve currently done it with dual radio links, one for ardupilot telemetry, and the other was my humidity/temp data (coming from a RPI zero). On the ground I used mission planner NEMA output to obtain altitudes and time, I then made a user app that parsed out time/altitude/humidity/temperature from their respective serial ports, displayed the data, and more importantly recorded it. This set up required 2 laptops because of the number of available usb/serial ports on my computers and the number of usb2serial adapters required.
What I really want to do is create additional parameters for humidity and temperature, have the RPI zero update those parameters at ~1Hz via the telem2 port on my pixhawk 2.1, download the flight logs obtain the data but most importantly be able to see the temp/humidity data real time in Mission planner. That way I can get rid of the additional 900MHz radio, remove a laptop from the setup and get rid of a lot of serial to usb adapters.
I’m probably most familiar with python as a programming language. As I said, I’ll be interfacing to the FC with a rpi zero over the uart. I understand i’ll need to create the parameters on the FC and somehow get the rpi to send temp/humidity messages to the FC. How do I go about doing that? Which of these tools do I need: pymavlink, mavproxy, dronekit, maverick??
Can anyone tell me where I should start or a block diagram of how it might work programmatically?
Wouldn’t it be easier to take the ardupilot telemetry to the pi zero over a serial connection, and then forward this through the pi zero radio link as well as your humidity/temp data?
I really don’t know, I don’t know where to begin really. However I would rather record on the craft so the data is available even if the radio link gets degraded or drops out, additionally I think I may use missionplanner to plot the data as well, via the log analysis tools.
This is doable by connecting your companion computer to the FC’s telem2 port and assembling + sending MAVlink packets via that port. When you send the packets, you need to specify a sysid and a compid. You can use sysid=1 and a compid that matches your onboard companion computer’s role. Here’s an example in C++/Arduino from an earlier project I worked on, which sends data using MAVlink DEBUG_VECT messages:
void DataRelay::SendSensorData(std::pair<int, int> smell)
{
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
// Pack a mavlink debug message to encode the sensor data
mavlink_msg_debug_vect_pack(
/*sysid*/ 1,
/*compid*/ MAV_COMP_ID_PATHPLANNER,
&msg,
/*name*/ "SENSOR",
/*time_boot_ms*/ millis(),
/*x*/ smell.first,
/*y*/ smell.second,
/*z*/ 0
);
// Copy the message to the send buffer
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
// Send the message via Serial1 to the FC's TELEM2 UART
Serial1.write(buf, len);
}
At the GCS, you will be able to see the MAVlink DEBUG_VECT messages under the compid associated with your companion computer. You can take those apart and analyze the data as needed. Here’s an example in python, running as a script in MissionPlanner:
def PacketHandler(o, message):
global _log
global _samples
global _uav
try:
# Debug_vect packets. These are sent by component 195 and encode sensor values.
if (message.msgid == MAVLink.MAVLINK_MSG_ID.DEBUG_VECT.value__) and \
("SENSOR" in bytes(message.data.name)):
# do whatever you want here with this data...
_samples.collect(cs.lat, cs.lng, cs.alt, cs.nav_bearing, message.data.x, message.data.y)
_log.Log("DEBUG_VECT/SENSOR: (" + str(_samples[-1].left) + "," + str(_samples[-1].right) + ")", VERBOSITY_MEDIUM)
except Exception as inst:
print inst
# somewhere in the init code...
# Subscribe to MAVlink messages
MAV.OnPacketReceived += PacketHandler
Let me know if I misunderstood what you want to do…