From e6752e43b264a97bec830c442df518f7200fd854 Mon Sep 17 00:00:00 2001 From: Mohammed Kabir Date: Fri, 5 Jun 2015 18:30:40 +0530 Subject: [PATCH] camera trigger : cleanup - still crashes --- src/modules/camera_trigger/camera_trigger.cpp | 55 +++++++++++-------- 1 file changed, 31 insertions(+), 24 deletions(-) diff --git a/src/modules/camera_trigger/camera_trigger.cpp b/src/modules/camera_trigger/camera_trigger.cpp index a694778014..7c7e5a14d1 100644 --- a/src/modules/camera_trigger/camera_trigger.cpp +++ b/src/modules/camera_trigger/camera_trigger.cpp @@ -142,6 +142,8 @@ CameraTrigger *g_camera_trigger; CameraTrigger::CameraTrigger() : pin(1), + _pollcall{}, + _firecall{}, _gpio_fd(-1), _polarity(0), _activation_time(0.0f), @@ -152,11 +154,13 @@ CameraTrigger::CameraTrigger() : _sensor_sub(-1), _vcommand_sub(-1), _trigger_pub(nullptr), - _trigger{} + _trigger{}, + _sensor{}, + _command{} { memset(&_trigger, 0, sizeof(_trigger)); - memset(&_command, 0, sizeof(_command)); memset(&_sensor, 0, sizeof(_sensor)); + memset(&_command, 0, sizeof(_command)); memset(&_pollcall, 0, sizeof(_pollcall)); memset(&_firecall, 0, sizeof(_firecall)); @@ -180,7 +184,6 @@ CameraTrigger::start() _gpio_fd = open(PX4FMU_DEVICE_PATH, 0); if (_gpio_fd < 0) { - warnx("GPIO device open fail"); stop(); } @@ -197,15 +200,15 @@ CameraTrigger::start() param_get(integration_time, &_integration_time); param_get(transfer_time, &_transfer_time); - ioctl(_gpio_fd, GPIO_SET_OUTPUT, pin); + px4_ioctl(_gpio_fd, GPIO_SET_OUTPUT, pin); if(_polarity == 0) { - ioctl(_gpio_fd, GPIO_SET, pin); /* GPIO pin pull high */ + px4_ioctl(_gpio_fd, GPIO_SET, pin); /* GPIO pin pull high */ } else if(_polarity == 1) { - ioctl(_gpio_fd, GPIO_CLEAR, pin); /* GPIO pin pull low */ + px4_ioctl(_gpio_fd, GPIO_CLEAR, pin); /* GPIO pin pull low */ } else { @@ -224,7 +227,9 @@ CameraTrigger::stop() hrt_cancel(&_firecall); hrt_cancel(&_pollcall); - delete camera_trigger::g_camera_trigger; + if (camera_trigger::g_camera_trigger != nullptr) { + delete (camera_trigger::g_camera_trigger); + } } void @@ -280,7 +285,7 @@ CameraTrigger::poll(void *arg) trig->_trigger.timestamp = trig->_sensor.timestamp; /* get IMU timestamp */ trig->_trigger.seq = trig->_trigger_seq++; - if (trig->_trigger_pub > 0) { + if (trig->_trigger_pub != nullptr) { orb_publish(ORB_ID(camera_trigger), trig->_trigger_pub, &trig->_trigger); } else { trig->_trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trig->_trigger); @@ -298,17 +303,18 @@ CameraTrigger::engage(void *arg) CameraTrigger *trig = reinterpret_cast(arg); trig->_gpio_fd = open(PX4FMU_DEVICE_PATH, 0); - - if(trig->_polarity == 0) /* ACTIVE_LOW */ + if(trig->_gpio_fd == -1) return; + + if(trig->_polarity == 0) // ACTIVE_LOW { - ioctl(trig->_gpio_fd, GPIO_CLEAR, trig->pin); + px4_ioctl(trig->_gpio_fd, GPIO_CLEAR, trig->pin); } - else if(trig->_polarity == 1) /* ACTIVE_HIGH */ + else if(trig->_polarity == 1) // ACTIVE_HIGH { - ioctl(trig->_gpio_fd, GPIO_SET, trig->pin); + px4_ioctl(trig->_gpio_fd, GPIO_SET, trig->pin); } - - close(trig->_gpio_fd); + + close(trig->_gpio_fd); } @@ -319,16 +325,17 @@ CameraTrigger::disengage(void *arg) CameraTrigger *trig = reinterpret_cast(arg); trig->_gpio_fd = open(PX4FMU_DEVICE_PATH, 0); - - if(trig->_polarity == 0) /* ACTIVE_LOW */ - { - ioctl(trig->_gpio_fd, GPIO_SET, trig->pin); - } - else if(trig->_polarity == 1) /* ACTIVE_HIGH */ - { - ioctl(trig->_gpio_fd, GPIO_CLEAR, trig->pin); - } + if(trig->_gpio_fd == -1) return; + if(trig->_polarity == 0) // ACTIVE_LOW + { + px4_ioctl(trig->_gpio_fd, GPIO_SET, trig->pin); + } + else if(trig->_polarity == 1) // ACTIVE_HIGH + { + px4_ioctl(trig->_gpio_fd, GPIO_CLEAR, trig->pin); + } + close(trig->_gpio_fd); }