aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/08_ardrone13
-rw-r--r--ROMFS/px4fmu_common/init.d/09_ardrone_flow13
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS4
-rwxr-xr-xTools/combin13632 -> 0 bytes
-rw-r--r--Tools/com.c191
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.c6
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.c10
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.c2
8 files changed, 36 insertions, 203 deletions
diff --git a/ROMFS/px4fmu_common/init.d/08_ardrone b/ROMFS/px4fmu_common/init.d/08_ardrone
index f6d82a5ec..7dbbb8284 100644
--- a/ROMFS/px4fmu_common/init.d/08_ardrone
+++ b/ROMFS/px4fmu_common/init.d/08_ardrone
@@ -8,7 +8,18 @@ echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
- # TODO
+ param set MC_ATTRATE_D 0
+ param set MC_ATTRATE_I 0
+ param set MC_ATTRATE_P 0.13
+ param set MC_ATT_D 0
+ param set MC_ATT_I 0.3
+ param set MC_ATT_P 5
+ param set MC_YAWPOS_D 0.1
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 1
+ param set MC_YAWRATE_D 0
+ param set MC_YAWRATE_I 0
+ param set MC_YAWRATE_P 0.15
param set SYS_AUTOCONFIG 0
param save
diff --git a/ROMFS/px4fmu_common/init.d/09_ardrone_flow b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
index 794342a0b..6333aae56 100644
--- a/ROMFS/px4fmu_common/init.d/09_ardrone_flow
+++ b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
@@ -8,7 +8,18 @@ echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
- # TODO
+ param set MC_ATTRATE_D 0
+ param set MC_ATTRATE_I 0
+ param set MC_ATTRATE_P 0.13
+ param set MC_ATT_D 0
+ param set MC_ATT_I 0.3
+ param set MC_ATT_P 5
+ param set MC_YAWPOS_D 0.1
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 1
+ param set MC_YAWRATE_D 0
+ param set MC_YAWRATE_I 0
+ param set MC_YAWRATE_P 0.15
param set SYS_AUTOCONFIG 0
param save
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 1f466e49f..4c4b0129e 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -207,7 +207,9 @@ then
if [ $MODE == autostart ]
then
# Telemetry port is on both FMU boards ttyS1
- mavlink start -b 57600 -d /dev/ttyS1
+ # but the AR.Drone motors can be get 'flashed'
+ # if starting MAVLink on them - so do not
+ # start it as default (default link: USB)
# Start commander
commander start
diff --git a/Tools/com b/Tools/com
deleted file mode 100755
index 1d80d4aa5..000000000
--- a/Tools/com
+++ /dev/null
Binary files differ
diff --git a/Tools/com.c b/Tools/com.c
deleted file mode 100644
index fa52dcb61..000000000
--- a/Tools/com.c
+++ /dev/null
@@ -1,191 +0,0 @@
-/*
- * Building: cc -o com com.c
- * Usage : ./com /dev/device [speed]
- * Example : ./com /dev/ttyS0 [115200]
- * Keys : Ctrl-A - exit, Ctrl-X - display control lines status
- * Darcs : darcs get http://tinyserial.sf.net/
- * Homepage: http://tinyserial.sourceforge.net
- * Version : 2009-03-05
- *
- * Ivan Tikhonov, http://www.brokestream.com, kefeer@brokestream.com
- * Patches by Jim Kou, Henry Nestler, Jon Miner, Alan Horstmann
- *
- */
-
-
-/* Copyright (C) 2007 Ivan Tikhonov
-
- This software is provided 'as-is', without any express or implied
- warranty. In no event will the authors be held liable for any damages
- arising from the use of this software.
-
- Permission is granted to anyone to use this software for any purpose,
- including commercial applications, and to alter it and redistribute it
- freely, subject to the following restrictions:
-
- 1. The origin of this software must not be misrepresented; you must not
- claim that you wrote the original software. If you use this software
- in a product, an acknowledgment in the product documentation would be
- appreciated but is not required.
- 2. Altered source versions must be plainly marked as such, and must not be
- misrepresented as being the original software.
- 3. This notice may not be removed or altered from any source distribution.
-
- Ivan Tikhonov, kefeer@brokestream.com
-
-*/
-
-#include <termios.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-#include <sys/signal.h>
-#include <sys/types.h>
-#include <sys/ioctl.h>
-#include <fcntl.h>
-#include <errno.h>
-
-int transfer_byte(int from, int to, int is_control);
-
-typedef struct {char *name; int flag; } speed_spec;
-
-
-void print_status(int fd) {
- int status;
- unsigned int arg;
- status = ioctl(fd, TIOCMGET, &arg);
- fprintf(stderr, "[STATUS]: ");
- if(arg & TIOCM_RTS) fprintf(stderr, "RTS ");
- if(arg & TIOCM_CTS) fprintf(stderr, "CTS ");
- if(arg & TIOCM_DSR) fprintf(stderr, "DSR ");
- if(arg & TIOCM_CAR) fprintf(stderr, "DCD ");
- if(arg & TIOCM_DTR) fprintf(stderr, "DTR ");
- if(arg & TIOCM_RNG) fprintf(stderr, "RI ");
- fprintf(stderr, "\r\n");
-}
-
-int main(int argc, char *argv[])
-{
- int comfd;
- struct termios oldtio, newtio; //place for old and new port settings for serial port
- struct termios oldkey, newkey; //place tor old and new port settings for keyboard teletype
- char *devicename = argv[1];
- int need_exit = 0;
- speed_spec speeds[] =
- {
- {"1200", B1200},
- {"2400", B2400},
- {"4800", B4800},
- {"9600", B9600},
- {"19200", B19200},
- {"38400", B38400},
- {"57600", B57600},
- {"115200", B115200},
- {NULL, 0}
- };
- int speed = B9600;
-
- if(argc < 2) {
- fprintf(stderr, "example: %s /dev/ttyS0 [115200]\n", argv[0]);
- exit(1);
- }
-
- comfd = open(devicename, O_RDWR | O_NOCTTY | O_NONBLOCK);
- if (comfd < 0)
- {
- perror(devicename);
- exit(-1);
- }
-
- if(argc > 2) {
- speed_spec *s;
- for(s = speeds; s->name; s++) {
- if(strcmp(s->name, argv[2]) == 0) {
- speed = s->flag;
- fprintf(stderr, "setting speed %s\n", s->name);
- break;
- }
- }
- }
-
- fprintf(stderr, "C-a exit, C-x modem lines status\n");
-
- tcgetattr(STDIN_FILENO,&oldkey);
- newkey.c_cflag = B9600 | CRTSCTS | CS8 | CLOCAL | CREAD;
- newkey.c_iflag = IGNPAR;
- newkey.c_oflag = 0;
- newkey.c_lflag = 0;
- newkey.c_cc[VMIN]=1;
- newkey.c_cc[VTIME]=0;
- tcflush(STDIN_FILENO, TCIFLUSH);
- tcsetattr(STDIN_FILENO,TCSANOW,&newkey);
-
-
- tcgetattr(comfd,&oldtio); // save current port settings
- newtio.c_cflag = speed | CS8 | CLOCAL | CREAD;
- newtio.c_iflag = IGNPAR;
- newtio.c_oflag = 0;
- newtio.c_lflag = 0;
- newtio.c_cc[VMIN]=1;
- newtio.c_cc[VTIME]=0;
- tcflush(comfd, TCIFLUSH);
- tcsetattr(comfd,TCSANOW,&newtio);
-
- print_status(comfd);
-
- while(!need_exit) {
- fd_set fds;
- int ret;
-
- FD_ZERO(&fds);
- FD_SET(STDIN_FILENO, &fds);
- FD_SET(comfd, &fds);
-
-
- ret = select(comfd+1, &fds, NULL, NULL, NULL);
- if(ret == -1) {
- perror("select");
- } else if (ret > 0) {
- if(FD_ISSET(STDIN_FILENO, &fds)) {
- need_exit = transfer_byte(STDIN_FILENO, comfd, 1);
- }
- if(FD_ISSET(comfd, &fds)) {
- need_exit = transfer_byte(comfd, STDIN_FILENO, 0);
- }
- }
- }
-
- tcsetattr(comfd,TCSANOW,&oldtio);
- tcsetattr(STDIN_FILENO,TCSANOW,&oldkey);
- close(comfd);
-
- return 0;
-}
-
-
-int transfer_byte(int from, int to, int is_control) {
- char c;
- int ret;
- do {
- ret = read(from, &c, 1);
- } while (ret < 0 && errno == EINTR);
- if(ret == 1) {
- if(is_control) {
- if(c == '\x01') { // C-a
- return -1;
- } else if(c == '\x18') { // C-x
- print_status(to);
- return 0;
- }
- }
- while(write(to, &c, 1) == -1) {
- if(errno!=EAGAIN && errno!=EINTR) { perror("write failed"); break; }
- }
- } else {
- fprintf(stderr, "\nnothing to read. probably port disconnected.\n");
- return -2;
- }
- return 0;
-}
-
diff --git a/src/modules/multirotor_att_control/multirotor_attitude_control.c b/src/modules/multirotor_att_control/multirotor_attitude_control.c
index c78232f11..8245aa560 100644
--- a/src/modules/multirotor_att_control/multirotor_attitude_control.c
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.c
@@ -62,15 +62,15 @@
#include <systemlib/param/param.h>
#include <drivers/drv_hrt.h>
-PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 0.3f);
+PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 2.0f);
PARAM_DEFINE_FLOAT(MC_YAWPOS_I, 0.15f);
PARAM_DEFINE_FLOAT(MC_YAWPOS_D, 0.0f);
//PARAM_DEFINE_FLOAT(MC_YAWPOS_AWU, 1.0f);
//PARAM_DEFINE_FLOAT(MC_YAWPOS_LIM, 3.0f);
-PARAM_DEFINE_FLOAT(MC_ATT_P, 0.2f);
+PARAM_DEFINE_FLOAT(MC_ATT_P, 6.8f);
PARAM_DEFINE_FLOAT(MC_ATT_I, 0.0f);
-PARAM_DEFINE_FLOAT(MC_ATT_D, 0.05f);
+PARAM_DEFINE_FLOAT(MC_ATT_D, 0.0f);
//PARAM_DEFINE_FLOAT(MC_ATT_AWU, 0.05f);
//PARAM_DEFINE_FLOAT(MC_ATT_LIM, 0.4f);
diff --git a/src/modules/multirotor_att_control/multirotor_rate_control.c b/src/modules/multirotor_att_control/multirotor_rate_control.c
index 0a336be47..adb63186c 100644
--- a/src/modules/multirotor_att_control/multirotor_rate_control.c
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.c
@@ -59,14 +59,14 @@
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
-PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.0f); /* same on Flamewheel */
-PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
-PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f);
+PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f); /* same on Flamewheel */
+PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.005f);
+PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.2f);
//PARAM_DEFINE_FLOAT(MC_YAWRATE_AWU, 0.0f);
//PARAM_DEFINE_FLOAT(MC_YAWRATE_LIM, 1.0f);
-PARAM_DEFINE_FLOAT(MC_ATTRATE_P, 0.0f); /* 0.15 F405 Flamewheel */
-PARAM_DEFINE_FLOAT(MC_ATTRATE_D, 0.0f);
+PARAM_DEFINE_FLOAT(MC_ATTRATE_P, 0.09f); /* 0.15 F405 Flamewheel */
+PARAM_DEFINE_FLOAT(MC_ATTRATE_D, 0.002f);
PARAM_DEFINE_FLOAT(MC_ATTRATE_I, 0.0f);
//PARAM_DEFINE_FLOAT(MC_ATTRATE_AWU, 0.05f);
//PARAM_DEFINE_FLOAT(MC_ATTRATE_LIM, 1.0f); /**< roughly < 500 deg/s limit */
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
index bf9578ea3..b7041e4d5 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
@@ -54,7 +54,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_D, 0.0f);
PARAM_DEFINE_FLOAT(MPC_XY_VEL_P, 0.2f);
PARAM_DEFINE_FLOAT(MPC_XY_VEL_I, 0.0f);
PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.0f);
-PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 10.0f);
+PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
PARAM_DEFINE_FLOAT(MPC_TILT_MAX, 0.5f);
int parameters_init(struct multirotor_position_control_param_handles *h)