camera_trigger : clean up console output

This commit is contained in:
Mohammed Kabir 2017-04-04 19:03:48 +02:00 committed by Lorenz Meier
parent 704de4f88f
commit ea890ecdd3
4 changed files with 7 additions and 4 deletions

View File

@ -73,9 +73,9 @@ void CameraInterfaceGPIO::trigger(bool enable)
void CameraInterfaceGPIO::info()
{
warnx("GPIO trigger mode, AUX pin state 1-6 : [%d][%d][%d][%d][%d][%d], polarity : %s",
_pins[0], _pins[1], _pins[2], _pins[3], _pins[4], _pins[5],
_polarity ? "ACTIVE_HIGH" : "ACTIVE_LOW");
PX4_INFO("GPIO trigger mode, pins enabled : [%d][%d][%d][%d][%d][%d], polarity : %s",
_pins[5], _pins[4], _pins[3], _pins[2], _pins[1], _pins[0],
_polarity ? "ACTIVE_HIGH" : "ACTIVE_LOW");
}
#endif /* ifdef __PX4_NUTTX */

View File

@ -11,6 +11,7 @@
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <board_config.h>
#include <px4_log.h>
#include "camera_interface.h"

View File

@ -145,7 +145,8 @@ void CameraInterfacePWM::turn_on_off(bool enable)
void CameraInterfacePWM::info()
{
warnx("PWM trigger mode - pin config: %d,%d,%d", _pins[0] + 1, _pins[1] + 1, _pins[2] + 1);
PX4_INFO("PWM trigger mode, pins enabled : [%d][%d][%d][%d][%d][%d]",
_pins[5], _pins[4], _pins[3], _pins[2], _pins[1], _pins[0]);
}
#endif /* ifdef __PX4_NUTTX */

View File

@ -10,6 +10,7 @@
#include <drivers/drv_hrt.h>
#include <systemlib/param/param.h>
#include <px4_log.h>
#include <uORB/topics/vehicle_status.h>
#include "camera_interface.h"