Hi everyone,
Does anyone have experience with configuring their own sensors onto the Pixhawk (I have an IRIS)? I purchased a gas sensor that I'd like to wire to it, does anyone know of any good resources to help me get started? I've downloaded the PX4 development environment from the Pixhawk developers website and have gone through some of the "getting started" instructions on there, I have been able to install the firmware through Eclipse as opposed to the Mission Planner. I also purchased 3-position and 5-position connectors for the analog inputs.
I was also wondering if there is a way to view the telemetry log data on Mission Planner during flight? If I did add this sensor, would data be saved through the telemetry logs or dataflash logs?
I appreciate whatever help I can get, thank you!
Kate
Replies
I had a bit of a play on the Pixhawk and managed to view live data from the ADC pins (13 in example) via telemetry. I simply read the adc pin and assigned the value to sonar_alt. I also altered the mavlink code to transmit sonar_alt even when it is disabled in the parameters. I could view the value live in MP as sonarrange and it is also available as mavlink_rangefinder_t.distance in the tlog. I note that the same message records the sonarvoltage parameter as well so you could potentially pass two separate readings by overriding this message.
GCS_Mavlink.pde (starting at line 486 in current master):
#if CONFIG_SONAR == ENABLED
static void NOINLINE send_rangefinder(mavlink_channel_t chan)
{
// exit immediately if sonar is disabled
if (!g.sonar_enabled) {
// return; commented out this line to force message to be sent
}
mavlink_msg_rangefinder_send(chan, sonar_alt * 0.01f, 0); // you can scale the parameters as you need. The 3rd param is supposed to be sonar voltage (not used in this code and is 0) and could potentially be another variable
}
#endif
UserCode.pde:
AP_HAL::AnalogSource *test_adc;
#ifdef USERHOOK_INIT
void userhook_init()
{
test_adc = hal.analogin->channel(13);
}
#endif
#ifdef USERHOOK_MEDIUMLOOP
void userhook_MediumLoop()
{
// put your 10Hz code here
sonar_alt=test_adc->voltage_latest();
}
#endif
Don't forget to uncomment USERHOOK_INIT and USERHOOK_MEDIUMLOOP in APM_Config.h
James,
Does the above work? Even though you have commented out the return so that the message gets sent, if Sonar is not enabled, the whole section of code in GCS_Mavlink.pde will not run because of the #if CONFIG_SONAR == ENABLED.
If you enable sonar, then you will also enable the sonar behaviors. I would have thought that you would have been better off leaving Sonar disabled and modifying the code to be;
// #if CONFIG_SONAR == ENABLED
static void NOINLINE send_rangefinder(mavlink_channel_t chan)
{
// exit immediately if sonar is disabled
// if (!g.sonar_enabled) {
// return; commented out this line to force message to be sent
// }
mavlink_msg_rangefinder_send(chan, sonar_alt * 0.01f, 0);
}
// #endif
Yep. Copy that. Soooo...it would be enabled by default.
Thanks.
J
Hi Ben,
This code should work fine on the APM - just use the appropriate ADC pin.
Hi,
Where is sonar_alt defined?
ArduCopter.pde line 571 (current master):
static int16_t sonar_alt;
I chose sonar_alt as sonar is not so commonly used. Obviously if you attempted to use this code with SONAR_ENABLE=1 then there would be problems. I think a better approach would be to declare a separate variable and then substitute this in the send_rangefinder() mavlink function. This would ensure that no other code was relying on sonar_alt being any particular value when SONAR_ENABLE=0.