aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2015-01-11 21:07:35 +0100
committerLorenz Meier <lm@inf.ethz.ch>2015-01-11 21:07:35 +0100
commita9a8cc691a0344d9a7651b1e51f73c9db4d9bdaa (patch)
treeda002eeb4df086627fc6505e78588f801748da43
parent0954ee74714373ee99740cbadb665874b95faa19 (diff)
downloadpx4-firmware-a9a8cc691a0344d9a7651b1e51f73c9db4d9bdaa.tar.gz
px4-firmware-a9a8cc691a0344d9a7651b1e51f73c9db4d9bdaa.tar.bz2
px4-firmware-a9a8cc691a0344d9a7651b1e51f73c9db4d9bdaa.zip
drivers/servo_gimbal: Added servo gimbal
-rw-r--r--makefiles/config_px4fmu-v2_default.mk1
-rw-r--r--src/drivers/servo_gimbal/gimbal.cpp534
-rw-r--r--src/drivers/servo_gimbal/module.mk42
3 files changed, 577 insertions, 0 deletions
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 577140f05..224385df1 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -43,6 +43,7 @@ MODULES += drivers/frsky_telemetry
MODULES += modules/sensors
MODULES += drivers/mkblctrl
MODULES += drivers/px4flow
+MODULES += drivers/servo_gimbal
#
# System commands
diff --git a/src/drivers/servo_gimbal/gimbal.cpp b/src/drivers/servo_gimbal/gimbal.cpp
new file mode 100644
index 000000000..01a1712a2
--- /dev/null
+++ b/src/drivers/servo_gimbal/gimbal.cpp
@@ -0,0 +1,534 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014, 2015 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gimbal.cpp
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Driver to control a gimbal - relies on input via telemetry or RC
+ * and output via the standardized control group #2 and a mixer.
+ */
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+#include <termios.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_range_finder.h>
+#include <drivers/device/device.h>
+#include <drivers/device/ringbuffer.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_command.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_attitude.h>
+
+#include <board_config.h>
+
+/* Configuration Constants */
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+#define GIMBAL_DEVICE_PATH "/dev/gimbal"
+
+#define GIMBAL_UPDATE_INTERVAL (50 * 1000)
+
+#define GIMBALIOCATTCOMPENSATE 1
+
+class Gimbal : public device::CDev
+{
+public:
+ Gimbal();
+ virtual ~Gimbal();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+protected:
+ virtual int probe();
+
+private:
+ float _min_distance;
+ float _max_distance;
+ work_s _work;
+ int _vehicle_command_sub;
+ int _att_sub;
+
+ bool _attitude_compensation;
+ bool _initialized;
+
+ orb_advert_t _actuator_controls_2_topic;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+ /**
+ * Initialise the automatic measurement state machine and start it.
+ *
+ * @note This function is called at open and error time. It might make sense
+ * to make it more aggressive about resetting the bus in case of errors.
+ */
+ void start();
+
+ /**
+ * Stop the automatic measurement state machine.
+ */
+ void stop();
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
+ void cycle();
+
+ /**
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
+
+
+};
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int gimbal_main(int argc, char *argv[]);
+
+Gimbal::Gimbal() :
+ CDev("Gimbal", GIMBAL_DEVICE_PATH),
+ _vehicle_command_sub(-1),
+ _att_sub(-1),
+ _attitude_compensation(false),
+ _initialized(false),
+ _actuator_controls_2_topic(-1),
+ _sample_perf(perf_alloc(PC_ELAPSED, "gimbal_read")),
+ _comms_errors(perf_alloc(PC_COUNT, "gimbal_comms_errors")),
+ _buffer_overflows(perf_alloc(PC_COUNT, "gimbal_buffer_overflows"))
+{
+ // disable debug() calls
+ _debug_enabled = false;
+
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+Gimbal::~Gimbal()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ ::close(_actuator_controls_2_topic);
+ ::close(_vehicle_command_sub);
+}
+
+int
+Gimbal::init()
+{
+ int ret = ERROR;
+
+ /* do regular cdev init */
+ if (CDev::init() != OK) {
+ goto out;
+ }
+
+ start();
+ ret = OK;
+
+out:
+ return ret;
+}
+
+int
+Gimbal::probe()
+{
+ return OK;
+}
+
+int
+Gimbal::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case GIMBALIOCATTCOMPENSATE:
+ _attitude_compensation = (arg != 0);
+ return OK;
+
+ default:
+ /* give it to the superclass */
+ return CDev::ioctl(filp, cmd, arg);
+ }
+}
+
+ssize_t
+Gimbal::read(struct file *filp, char *buffer, size_t buflen)
+{
+ return 0;
+}
+
+void
+Gimbal::start()
+{
+
+ /* schedule a cycle to start things */
+ work_queue(LPWORK, &_work, (worker_t)&Gimbal::cycle_trampoline, this, 1);
+}
+
+void
+Gimbal::stop()
+{
+ work_cancel(LPWORK, &_work);
+}
+
+void
+Gimbal::cycle_trampoline(void *arg)
+{
+ Gimbal *dev = static_cast<Gimbal *>(arg);
+
+ dev->cycle();
+}
+
+void
+Gimbal::cycle()
+{
+
+ if (!_initialized) {
+ /* get a subscription handle on the vehicle command topic */
+ _vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command));
+
+ /* get a publication handle on actuator output topic */
+ struct actuator_controls_s zero_report;
+ memset(&zero_report, 0, sizeof(zero_report));
+ zero_report.timestamp = hrt_absolute_time();
+ _actuator_controls_2_topic = orb_advertise(ORB_ID(actuator_controls_2), &zero_report);
+
+ if (_actuator_controls_2_topic < 0) {
+ warnx("advert err");
+ }
+
+ _initialized = true;
+ }
+
+ bool updated = false;
+
+ perf_begin(_sample_perf);
+
+ float roll = 0.0f;
+ float pitch = 0.0f;
+
+
+ if (_attitude_compensation) {
+ if (_att_sub < 0) {
+ _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ }
+
+ vehicle_attitude_s att;
+
+ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &att);
+
+ roll = -att.roll;
+ pitch = -att.pitch;
+
+ updated = true;
+
+ }
+
+ struct vehicle_command_s cmd;
+
+ bool cmd_updated;
+
+ orb_check(_vehicle_command_sub, &cmd_updated);
+
+ if (cmd_updated) {
+
+ orb_copy(ORB_ID(vehicle_command), _vehicle_command_sub, &cmd);
+
+ //debug("cmd: %d, param1: %8.4f param2: %8.4f", (double)cmd.command, (double)cmd.param1, (double)cmd.param2);
+
+ if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL && cmd.param7 == 2) {
+
+ /* Convert to range -1 ... 1, which corresponds to -180deg ... 180deg */
+ roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param1;
+ pitch += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param2;
+
+ updated = true;
+
+ }
+
+ // XXX change this to the real quaternion command
+ if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT && cmd.param7 == 2) {
+
+ /* Convert to range -1 ... 1, which corresponds to -180deg ... 180deg */
+ roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param1;
+ pitch += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param2;
+
+ updated = true;
+
+ }
+ }
+
+ if (updated) {
+
+ struct actuator_controls_s controls;
+
+ /* fill in the final control values */
+ controls.timestamp = hrt_absolute_time();
+ controls.control[0] = roll;
+ controls.control[1] = pitch;
+
+ /* publish it */
+ orb_publish(ORB_ID(actuator_controls_2), _actuator_controls_2_topic, &controls);
+
+ }
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ perf_end(_sample_perf);
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(LPWORK,
+ &_work,
+ (worker_t)&Gimbal::cycle_trampoline,
+ this,
+ USEC2TICK(GIMBAL_UPDATE_INTERVAL));
+}
+
+void
+Gimbal::print_info()
+{
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_comms_errors);
+ perf_print_counter(_buffer_overflows);
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace gimbal
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+const int ERROR = -1;
+
+Gimbal *g_dev;
+
+void start();
+void stop();
+void test();
+void reset();
+void info();
+
+/**
+ * Start the driver.
+ */
+void
+start()
+{
+ if (g_dev != nullptr) {
+ errx(1, "already started");
+ }
+
+ /* create the driver */
+ g_dev = new Gimbal();
+
+ if (g_dev == nullptr) {
+ goto fail;
+ }
+
+ if (OK != g_dev->init()) {
+ goto fail;
+ }
+
+ exit(0);
+
+fail:
+
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Stop the driver
+ */
+void stop()
+{
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+
+ } else {
+ errx(1, "driver not running");
+ }
+
+ exit(0);
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+ int fd = open(GIMBAL_DEVICE_PATH, O_RDONLY);
+
+ if (ioctl(fd, GIMBALIOCATTCOMPENSATE, 1) < 0) {
+ err(1, "failed enabling compensation");
+ }
+
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(GIMBAL_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "failed ");
+ }
+
+ // if (ioctl(fd, GIMBALIOCATTCOMPENSATE, 1) < 0) {
+ // err(1, "failed enabling compensation");
+ // }
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr) {
+ errx(1, "driver not running");
+ }
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+} // namespace
+
+int
+gimbal_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+ */
+ if (!strcmp(argv[1], "start")) {
+ gimbal::start();
+ }
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop")) {
+ gimbal::stop();
+ }
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test")) {
+ gimbal::test();
+ }
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset")) {
+ gimbal::reset();
+ }
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
+ gimbal::info();
+ }
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+} \ No newline at end of file
diff --git a/src/drivers/servo_gimbal/module.mk b/src/drivers/servo_gimbal/module.mk
new file mode 100644
index 000000000..5699b702a
--- /dev/null
+++ b/src/drivers/servo_gimbal/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2014, 2015 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Makefile to build the gimbal high-level controller
+#
+
+MODULE_COMMAND = servo_gimbal
+
+SRCS = gimbal.cpp
+
+MAXOPTIMIZATION = -Os