mpaperno / jMAVSim

Simple multirotor simulator with MAVLink protocol support. Fixed, modified and enhanced fork of the original. Supports AutoQuad HILS.
BSD 3-Clause "New" or "Revised" License
2 stars 3 forks source link

Immediate flipping #1

Closed h3ifri closed 8 years ago

h3ifri commented 8 years ago

Hi Max,

just had some time to check jMAVSim with aqfc-mp-v7.1.1919-hwv8.6-quatos-hils. Everything is working until I try to take off. The copter is not flyable an immediately flips into ground. It looks like there is something wrong with my motor mix, but it's hard to tell whats exactly going wrong. It's the same with Quatos and PID.

I used the params file from the wiki, the only changes I made was to disable the gimbals ports, because I have the ESC's connected to them. Maybe the gimbal outputs should be disabled in gimbalInit() / gimbalUpdate() as you did in motorsSendValues() while in SIM mode. I did not disable the gimbal ports at first and ended up with a spinning motor ;)

Here is my complete params file: PARAMS-HILS.txt

I would be happy if you can give me a hint what's going wrong.

Cheers, Heiko

mpaperno commented 8 years ago

Hi Heiko,

Thanks for trying it out. I cannot figure out the flipping issue, despite many attempts and several helpful testers. There is one other person besides me for whom I know it works, on multiple computers and different M4s (and same here). For at least 3 others, and now you, it just flips out of control. I'm at a loss to explain it.

All the config params I've looked at always seem fine, no significant differences from mine or the other working version. The only time I get the same behavior is when the config is wrong, like motor mix or IMU flip/rotate... just like a real AQ.

Very good point about the gimbal outputs, I hadn't thought of that! Actually even preventing the motor outputs was an afterthought because I had only been testing with desk-bound AQ boards until a certain point. Sorry about that.

I removed the gimbal outputs from the posted config file, and added relevant notes to the instructions. That should avoid any nasty surprises.

Hopefully something will come to light soon regarding the flipping. It's frustrating w/out being able to recreate the issue first-hand.

Cheers, -Max

h3ifri commented 8 years ago

Hi Max,

are the HIL_CONTROLS in MAVLinkHILSystem the transmitter stick values? If so, there is somthing strange. I only increased throttle on my transmitter, but the values seem to change randomly:

Time: 1461221899390 Roll: 0.0 Pitch: 0.034676436334848404 Yaw: 0.1706959754228592 Throttle: 0.7572649717330933
Time: 1461221899894 Roll: 0.0 Pitch: 0.034676436334848404 Yaw: 0.34358975291252136 Throttle: 0.653235673904419
Time: 1461221900399 Roll: 0.021489622071385384 Pitch: 0.034676436334848404 Yaw: 0.47863247990608215 Throttle: 0.5843712091445923
Time: 1461221900903 Roll: 0.9201465249061584 Pitch: 0.034676436334848404 Yaw: 1.0 Throttle: 0.0
Time: 1461221901406 Roll: 0.9357753396034241 Pitch: 0.034676436334848404 Yaw: 1.0 Throttle: 0.0
Time: 1461221901911 Roll: 0.042490843683481216 Pitch: 0.03492063656449318 Yaw: 0.5015873312950134 Throttle: 0.5711843967437744
Time: 1461221902415 Roll: 0.6830281019210815 Pitch: 0.03492063656449318 Yaw: 0.9582417607307434 Throttle: 0.0
Time: 1461221902918 Roll: 0.0 Pitch: 0.034676436334848404 Yaw: 0.4583638608455658 Throttle: 0.7072039246559143
Time: 1461221903423 Roll: 0.0 Pitch: 0.034676436334848404 Yaw: 0.0 Throttle: 1.0
Time: 1461221903926 Roll: 0.04981685057282448 Pitch: 0.034676436334848404 Yaw: 0.49548229575157166 Throttle: 0.7711843848228455
Time: 1461221904430 Roll: 0.2510378658771515 Pitch: 0.034676436334848404 Yaw: 0.6442002654075623 Throttle: 0.8058608174324036
Time: 1461221904934 Roll: 0.26617828011512756 Pitch: 0.03492063656449318 Yaw: 0.6561660766601562 Throttle: 0.8732600808143616
Time: 1461221905438 Roll: 0.36849817633628845 Pitch: 0.034676436334848404 Yaw: 0.7323565483093262 Throttle: 0.8949939012527466
Time: 1461221905943 Roll: 0.3848595917224884 Pitch: 0.034676436334848404 Yaw: 0.7438339591026306 Throttle: 0.8920634984970093

Is this normal?

Cheers, Heiko

mpaperno commented 8 years ago

Hi Heiko,

Those are actually motor outputs from AQ (scaled to 0-1). The names (roll/pitch/etc) are misleading, they're really motors 1-4 (or A-D as in AQ frame diagrams).

Seems strange that "pitch" output is so much lower than the others (in many cases). That would certainly cause a flip... Or if the numbers are jumping a lot, that would be strange. How are you logging this? Assuming the timestamps are in ms, is the logging real-time or delayed? The HIL_CONTROLS message should be coming in at 400Hz.

Best, -Max

On Thu, Apr 21, 2016, at 03:07 AM (-0400), funth1ngs notifications@github.com wrote:

Hi Max,

are the HIL_CONTROLS in MAVLinkHILSystem the transmitter stick values? If so, there is somthing strange. I only increased throttle on my transmitter, but the values seem to change randomly:

|Time: 1461221899390 Roll: 0.0 Pitch: 0.034676436334848404 Yaw: 0.1706959754228592 Throttle: 0.7572649717330933 Time: 1461221899894 Roll: 0.0 Pitch: 0.034676436334848404 Yaw: 0.34358975291252136 Throttle: 0.653235673904419 Time: 1461221900399 Roll: 0.021489622071385384 Pitch: 0.034676436334848404 Yaw: 0.47863247990608215 Throttle: 0.5843712091445923 Time: 1461221900903 Roll: 0.9201465249061584 Pitch: 0.034676436334848404 Yaw: 1.0 Throttle: 0.0 Time: 1461221901406 Roll: 0.9357753396034241 Pitch: 0.034676436334848404 Yaw: 1.0 Throttle: 0.0 Time: 1461221901911 Roll: 0.042490843683481216 Pitch: 0.03492063656449318 Yaw: 0.5015873312950134 Throttle: 0.5711843967437744 Time: 1461221902415 Roll: 0.6830281019210815 Pitch: 0.03492063656449318 Yaw: 0.9582417607307434 Throttle: 0.0 Time: 1461221902918 Roll: 0.0 Pitch: 0.034676436334848404 Yaw: 0.4583638608455658 Throttle: 0.7072039246559143 Time: 1461221903423 Roll: 0.0 Pitch: 0.034676436334848404 Yaw: 0.0 Throttle: 1.0 Time: 1461221903926 Roll: 0.04981685057282448 Pitch: 0.034676436334848404 Yaw: 0.49548229575157166 Throttle: 0.7711843848228455 Time: 1461221904430 Roll: 0.2510378658771515 Pitch: 0.034676436334848404 Yaw: 0.6442002654075623 Throttle: 0.8058608174324036 Time: 1461221904934 Roll: 0.26617828011512756 Pitch: 0.03492063656449318 Yaw: 0.6561660766601562 Throttle: 0.8732600808143616 Time: 1461221905438 Roll: 0.36849817633628845 Pitch: 0.034676436334848404 Yaw: 0.7323565483093262 Throttle: 0.8949939012527466 Time: 1461221905943 Roll: 0.3848595917224884 Pitch: 0.034676436334848404 Yaw: 0.7438339591026306 Throttle: 0.8920634984970093 |

Is this normal?

Cheers, Heiko

— You are receiving this because you commented. Reply to this email directly or view it on GitHub https://github.com/mpaperno/jMAVSim/issues/1#issuecomment-212776275

h3ifri commented 8 years ago

Ah, OK.

Wanted to check if there is something wrong with the transmitter values, becuase if I move my ptich / roll stick into any end position, it still flips randomly.

I printed them every 500ms:

@@ -31,4 +31,6 @@ public class MAVLinkHILSystem extends MAVLinkSystem {
     private ScheduledExecutorService executor;
     SensorMessageThread msgThread;
+    private long debugMillis = System.currentTimeMillis();
+    private static final int DEBUG_INTERVAL = 500;

     /**
@@ -56,4 +58,10 @@ public class MAVLinkHILSystem extends MAVLinkSystem {
                     msg.getDouble("aux2"), msg.getDouble("aux3"), msg.getDouble("aux4"));
             vehicle.setControl(control);
+            if (System.currentTimeMillis() > debugMillis) {
+                debugMillis = System.currentTimeMillis() + DEBUG_INTERVAL;
+                System.out.println("Time: " + System.currentTimeMillis() + " Roll: " + msg.getDouble("roll_ailerons")
+                       + " Pitch: " + msg.getDouble("pitch_elevator") + " Yaw: " + msg.getDouble("yaw_rudder")
+                        + " Throttle: " + msg.getDouble("throttle"));
+            }
         } else if ("HEARTBEAT".equals(msg.getMsgName())) {
             if (!gotHeartBeat && !stopped) {

Cheers, Heiko

mpaperno commented 8 years ago

One thing I've been wondering about is if there is a communications delay being introduced somewhere. For instance I've noticed sometimes that USB may buffer serial data... some sort of delay due to buffering would be disastrous for the sim. It would also be hard to spot, because at quick glance all the I/O data looks correct. But it may be delayed by several ms and we'd never notice just by looking at it.

On the software side we could log the time_usec timestamp in the HIL_CONTROLS messages, but need to sync that AQ onboard time to real/sim time somehow.

To test lag in the other direction I think I'll need to add some logging in the firmware code. Although one way may be to test the lag between a reset command in the sim (space bar) and the resulting change in logged UKF values on AQ.

In fact that should give a good "trigger" indicator to synch onboard time to sim fime. AQ logs at 200Hz, so that should be fairly precise.

At any rate, I think you're on the right track with needing to log some values to narrow down what's going on.

-Max

h3ifri commented 8 years ago

Hi Max,

how is AQ noticed about the UKF Reset? Couldn't find anything directly in the key handler.

With the following changes I get dalys from 4-14 ms.

@@ -77,5 +85,9 @@ public class MAVLinkHILSystem extends MAVLinkSystem {
             }
         } else if ("STATUSTEXT".equals(msg.getMsgName())) {
+            if (msg.getString("text").equals("HILSIM: UKF reset completed.") && Visualizer3D.lastResetMs > 0) {
+                System.out.println("Delay: " + (System.currentTimeMillis() - Visualizer3D.lastResetMs) + "ms");
+            }
             System.out.println("MSG: " + msg.getString("text"));
+
         }
     }
@@ -47,2 +47,4 @@ public class Visualizer3D extends JFrame {
     public static final int       FPS_TARGET = 60;  // target frames per second
+
+    public static long lastResetMs = 0;

@@ -1076,4 +1078,4 @@ public class Visualizer3D extends JFrame {
                 case KeyEvent.VK_SPACE :
+                    lastResetMs = System.currentTimeMillis();
                     resetObjectRAV(vehicleViewObject, true);
-                    
                     resetView();

Cheers, Heiko

mpaperno commented 8 years ago

The sim sets an indicator bit in the HIL_SENSOR message. So first the flag is set in the vehicle sensors, then read out and reset when the next message is sent.

https://github.com/mpaperno/jMAVSim/blob/master/src/me/drton/jmavsim/MAVLinkHILSystem.java#L170

BTW, the reporting panel in the sim can be useful for checking status or displaying output.

Cheers, -Max

h3ifri commented 8 years ago

Hi Max,

I measured the looptime of the incoming HIL_CONTROLS message. The AVG is between 395 Hz and 405 Hz in one ReportUpdater update() cycle (250ms). The min/max between a single HIL_CONTROLS message is 0/12500 us. So there is definitely some buffering.

Then I tried to sync the AQ time to the SIM time on a UKF reset to compare the offsets for each HIL_CONTROLS message. That didn't work very well, because I guess the clock sources are not stable enough.

What do you think about this: In the HIL_CONTROLS message, AQ could send the timestamp of the latest HIL_SENSOR message instead of it's on time? Maybe this helps to calculate min/max delays.

Cheers, Heiko

bluuu commented 8 years ago

Heiko: did you do TARE before flight ? (only guess ...)

h3ifri commented 8 years ago

Hi bluuu!

Yes, my board is tared. But since the onboard sensors aren't used in simulation, I would say it doesn't even matter.

Cheers, Heiko

bluuu commented 8 years ago

for initial level is important (i asked because all works for me and i can't recreate flips on start ...)

mpaperno commented 8 years ago

Hi Heiko,

The AVG is between 395 Hz and 405 Hz

So that's right-on then, all messages are coming through.

The min/max between a single HIL_CONTROLS message is 0/12500 us.

I guess I'm not sure what this means... It measured zero micros between consecutive messages? And 12500 micros is 80 Hz...

What do you think about this: In the HIL_CONTROLS message, AQ could send the timestamp of the latest HIL_SENSOR message instead of it's on time? Maybe this helps to calculate min/max delays.

I think that's a great idea. I'll prepare a new firmware with that. Which M4 revision are you using to test? v2?

did you do TARE before flight ?

The tare should have no effect. It does reset the UKF, but that should be the same as doing a reset at the start of the sim or with the space bar. Adam, does yours act differently if you don't tare before flying?

BTW, Heiko, Adam here (bluuu) is the other person for whom the sim works. I've invited the others to this thread as well.

Cheers, -Max

bluuu commented 8 years ago

The tare should have no effect. It does reset the UKF, but that should be the same as doing a reset at the start of the sim or with the space bar. Adam, does yours act differently if you don't tare before flying?

ok, my bad

i used TARE in previous version where was no UKF reset by space bar ... and it was a habit for me ;) but ... i must check it better because it seems to me that i observed temperature drift ... must check ...

h3ifri commented 8 years ago

Hi Max,

yep I measured 0us, which should mean that something comes out of a buffer? Here are my changes to your code: changes.zip

My M4 is V2.

Cheers, Heiko

mpaperno commented 8 years ago

Heiko, here you go... http://max.wdg.us/AQ/aqfc-mp-v7.1.1922-hwv8.6-quatos-hils.zip

So the timestamp in HIL_CONTROLS is now the timestamp from the last received HIL_SENSOR message.

This has some unrelated nav module changes which I'm working on... not completely tested so probably best not to use this version for real flying.

Thanks! -Max

h3ifri commented 8 years ago

Hi Max,

thank you!

The average delay between the timestamp in HIL_CONTROLS and current system time is arround 6000 us. The min/max values are arround 1000/15000 us. It happens that I receive 4-5 HIL_CONTROLS messages with the same timestamp.

I will switch OS to Linux and try again.

Do you think the timing is bad enough to cause the flips?

Is the control loop on AQ somehow coupled to the HIL_SENSOR messages, or ist it running on a fixed frequency?

I also connected AQ via the second COM port to QGCS. Although the HUD is perfectly level, the motor outputs in the diagnostic widget are very uneven.

Cheers, Heiko

mpaperno commented 8 years ago

Brilliant, that's the kind of diagnostics we need.

I'm not really sure about the 6ms delay, but it does seem reasonable. 15ms does not. But I think I need to run the same test here and check the numbers on a working version.

Part of the problem with checking timing is that the sim is actually only sending ms-accuracy timestamps (here). That's probably why you're seeing duplicates coming back.

We may be able to improve on that by doing something like this in MAVLinkHILSystem...

Declare a new member and init it at startup to nanoTime():

public class MAVLinkHILSystem extends MAVLinkSystem { 
    ....
    private long startTime = 0L;

public MAVLinkHILSystem(....) {
    ....
    startTime  = System.nanoTime();
}

Then send the difference ni the HIL_SENSORS message:

private final class SensorMessageThread implements Runnable {
    ....
    public void run() {
        ....
        long tu = (System.nanoTime() - this.startTime) / 1000;   // Time in us
        ....

I think I'll implement that to try. The question then will be how accurate the system clock/timer is.

I'm very curious about your results with Linux. Uncharted territory! :)

Thanks, -Max

mpaperno commented 8 years ago

Errr.. actually it can all just be moved to the SensorMessageThread.

private final class SensorMessageThread implements Runnable {
    private long startTime = System.nanoTime();
    ....
    public void run() {
        ....
        long tu = (System.nanoTime() - this.startTime) / 1000L;   // Time in us
        ....

-Max

mpaperno commented 8 years ago

Is the control loop on AQ somehow coupled to the HIL_SENSOR messages, or ist it running on a fixed frequency?

Fixed frequency @ 400Hz. This also dictates the motor output frequency (and HIL_CONTROLS).

-Max

h3ifri commented 8 years ago

Hi Max,

Part of the problem with checking timing is that the sim is actually only sending ms-accuracy timestamps (here). That's probably why you're seeing duplicates coming back.

My results are already with nsec timestamps.

Here is a diff against your latest master: changes.zip (probably not the best code, but it should work...)

If you can run it, we can compare the values.

Cheers, Heiko

mpaperno commented 8 years ago

System.nanoTime() can't be used quite like that... https://docs.oracle.com/javase/7/docs/api/java/lang/System.html#nanoTime%28%29

I tried your code but the HUD jumps all over the place... because AQ will ignore SIM_SENSOR messages which are out of sequence.

I tried with the change I suggested above and it works in terms of flying the AQ, but messes up the new statistics calculations (was getting negative avg and unreasonably high min/max values).

So I made the following changes (against your version)...

@46
+    private long startTime = System.nanoTime();

@69
-            debugHilControlUpdate(System.nanoTime() / 1000, msg.getLong("time_usec"));
+            debugHilControlUpdate((System.nanoTime() - this.startTime) / 1000, msg.getLong("time_usec"));

@223
+        private long startTime = System.nanoTime();

@230
-            hilMsgSendMicros = System.nanoTime() / 1000; // Time in us
+            hilMsgSendMicros = (System.nanoTime() - this.startTime) / 1000L;   // Time in us

And I get the following results (AvgMsgDelay Min varies between shown and ~6000)

MAVLinkHILSystem
================
RecvLoopFreq: 400.8302 Hz (Min/Max: 0/12032 us)
AvgMsgDelay: 7947 us (Min/Max: 3992/15036 us)

How does this compare?

Thanks, -Max

mpaperno commented 8 years ago

The message delay calc wasn't quite right...

@160
-        long msgOffset = tSim - tMsg;
+        long msgOffset = hilMsgSendMicros - tMsg;

Now I get:

MAVLinkHILSystem
================
RecvLoopFreq: 400.7698 Hz (Min/Max: 0/12099 us)
AvgMsgDelay: 3521 us (Min/Max: 0/10041 us)

The average fluctuates from ~3000 to ~5500 or so. The Min is mostly zero but sometimes is close to 2000... but I think there are some logic bugs in how the min is tracked.

-Max

h3ifri commented 8 years ago

Hi Max,

the flips are the same in Linux.

I applied your changes (expect the one from you last comment) and get: AvgMsgDelay: 8000-8500, Min: ~3500-4000, Max: ~15000

With your last change I get: AvgMsgDelay: 4000-5000, Min: ~0-1000, Max: ~12000

The message delay calc wasn't quite right...

I had this before, but changed it because hilMsgSendMicros is updated in the SensorMessageThread, and with your changes you only calculate the delay between the last HIL_SENSOR message and current timestamp of the HIL_CONTROLS message.

Cheers, Heiko

mpaperno commented 8 years ago

Hi Heiko,

Yes, I see your point about the message timings. I think we'd need to declare startTime in the parent thread and use the same value for sending the message and checking the received timestamps. Otherwise we're not comparing real times to each other, due to the way nanoTime() works.

At any rate, I think the tests so far show that delay is not the problem... ?

I also connected AQ via the second COM port to QGCS. Although the HUD is perfectly level, the motor outputs in the diagnostic widget are very uneven.

That's ultimately what we need to track down then. If you try "flying" the AQ w/out the Sim running at all (just watching diagnostic telemetry), do you see even motor outputs (assuming the physical AQ board is level, or close to it)?

Out of curiosity, how is your M4 powered? Just USB, or are you using an adapter board (or similar) with external power?

Thanks, -Max

h3ifri commented 8 years ago

Hi Max!

At any rate, I think the tests so far show that delay is not the problem... ?

I can only guess, but yes, I would say so.

I also connected AQ via the second COM port to QGCS. Although the HUD is perfectly level, the motor outputs in the diagnostic widget are very uneven.

I have to take that back, they are not always "very" uneven. I logged a flip at 400Hz, maybe it helps to track down the problem: jMAVSim-DEBUG.zip

To rule out my config on the AQ, I use PID controller, and here is my motor mix (standard Quad-X mix):

[META]
ConfigId=0
Motors=4
PortOrder=1, 2, 3, 4
ImageFile=quad_x.mix
Craft=MAV 234

[Throttle]
Motor1=100
Motor2=100
Motor3=100
Motor4=100

[Pitch]
Motor1=100.000000
Motor2=100.000000
Motor3=-100.000000
Motor4=-100.000000

[Roll]
Motor1=100.000000
Motor2=-100.000000
Motor3=-100.000000
Motor4=100.000000

[Yaw]
Motor1=-100.000000
Motor2=100.000000
Motor3=-100.000000
Motor4=100.000000

Out of curiosity, how is your M4 powered? Just USB, or are you using an adapter board (or similar) with external power?

I have one of Jörgs adapter boards and use external power (8V power supply or 3S LiPo).

Here is something I noticed with the position of the motors in the report window:

ROTOR #0
Pos: +0,11; +0,11; +0;
ROTOR #1
Pos: -0,11; -0,11; +0;
ROTOR #2
Pos: +0,11; -0,11; +0;
ROTOR #3
Pos: -0,11; +0,11; +0;

Should'n the signs look something like this?

+ +
+ -
- -
- +

Tried to figure out the math in vehicle config, but have some trouble to completely understand it, so I couldn't say if the motor positions are maybe a part of the problem.

Cheers, Heiko

mpaperno commented 8 years ago

Hi Heiko,

You need to run the sim with -ap aq option, or changeDEFAULT_AUTOPILOT_TYPE at the top of Simulator.java. The port order should look like:

ROTOR #0
Position: +000.07071; -000.07071; +000.00000; 

ROTOR #1
Position: +000.07071; +000.07071; +000.00000; 

ROTOR #2
Position: -000.07071; +000.07071; +000.00000; 

ROTOR #3
Position: -000.07071; -000.07071; +000.00000;

I'll check the log a bit later and compare to a logged run here, thanks!

-Max

h3ifri commented 8 years ago

Hi Max,

got it working, flips are gone!!! =)

You need to run the sim with -ap aq option, or change DEFAULT_AUTOPILOT_TYPE at the top of Simulator.java.

I used "-ap aq", but somehow the "==" comparsion wasn't working, that's weird:

@@ -189,5 +189,5 @@ public class Simulator implements Runnable {
         // Create vehicle with sensors
         AbstractMulticopter vehicle;
-        if (autopilotType == "aq")
+        if (autopilotType.equals("aq"))
             vehicle = buildAQ_leora();
         else
@@ -201,5 +201,5 @@ public class Simulator implements Runnable {
         connHIL.addNode(hilSystem);

-        if (autopilotType == "aq") {
+        if (autopilotType.equals("aq")) {
             hilSystem.setHeartbeatInterval(0);
             DEFAULT_CAM_ROLL_CHAN = 6;

Thanks for your help tracking it down!

Cheers, Heiko

mpaperno commented 8 years ago

What?? That was it? equals() vs ==? :-O

mpaperno commented 8 years ago

What about in Quadcopter.java @36?

if (style == "cw_fr") {

-Max

h3ifri commented 8 years ago

This one seems to work... But I guess it's better to also change it to equals() ;)

http://stackoverflow.com/a/513839

Cheers, Heiko

mpaperno commented 8 years ago

I just had that page open :) I guess == is a bad habit! Wow, I'm going to get this fix out to the other guys and see what happens.

So it's totally random that it works here and for Adam? Weird. But if this fixes it, I'm not complaining!

Thanks! -Max

h3ifri commented 8 years ago

I hope it works for them, please let me know.

Cheers, Heiko

ChristofSchmid commented 8 years ago

Gents Thanks a lot for your tremendous work. Unfortunately I can not test the solution. I am abroad for a week and did not bring the equipment with me. Cheers Christof

mpaperno commented 8 years ago

We'll see what they get...

With the old code (with ==), I can recreate the port order issue here when I use -ap aq on the command line. But when DEFAULT_AUTOPILOT_TYPE = "aq", it always works (if not also passed via cmd-line). Since I think everyone else was using my pre-built versions with "aq" as default, I wonder if this is also their problem.

Of course I just realized that my instructions say to use -ap aq and Adam probably never used that because he read an earlier version of the instructions which didn't include that. OK, now I'm very hopeful again! :)

Heiko, did you try a pre-built version originally, or did you start with building your own right away?

Thanks, -Max

ChristofSchmid commented 8 years ago

Hi Max

I was using this:

java -Xmx1g -jar jmavsim_run.jar -ap aq -serial COM5 2400 –max

Cheers

Christof

mpaperno commented 8 years ago

Yep, that would do it. I've also found that the -Xmx switch seems unnecessary... the sim seems to use whatever RAM it actually needs.

Anyway, this fix sounds very promising!

-Max

h3ifri commented 8 years ago

Hi Max,

I only used my own builds.

Here are my command line options: -ap aq -serial COM3 2400 -no-gimbal

Cheers, Heiko

afernan commented 8 years ago

Running here also !

I used all same staff than previously but without the "-ap aq", so: java -jar jmavsim_run.jar -serial COM14 2400

Congratulaciones for the finding!

Angel

afernan commented 8 years ago

1

I got about 50% of CPU use with all shown in image open (NUC i5) Angel

h3ifri commented 8 years ago

Hi Angel,

not related to this problem, but can you please try if an Orbit waypoint works for you in the SIM? I'm currently trying this, but the radius is much larger then it should.

Cheers, Heiko

mpaperno commented 8 years ago

Heiko, I'm forever grateful to you for solving this. It's been bugging the hell out of me for a month, no pun intended. That will teach me for not following my own instructions!

I haven't tried an orbit wpt yet. How is the rest of it behaving? I've found that if the computer is too slow or busy, the first thing to act up is the navigation functions (eg. starts circling while in PH) and then also the ACC bias, to the point where it gets confused about what "level" is and starts drifting severely. The ACC bias is never a problem in rate (acro) mode, and the performance of the whole system is much less important in rate mode (which makes sense of course).

Thanks again, I'm so relieved to have this solved!

-Max

afernan commented 8 years ago

Hi Max:

I´ve tried a 5m radius Orbit. It did the work, but as time goes it starts to do those anoying circles like toilet.

In fact PH does behaves the same. It starts doing well but after some seconds toilet circles starts and grows with time. I´ve tryed to tune a bit Nav posistion params without success.

Mission is working quite well for me, as RTL.

Angel

On Sun, Apr 24, 2016 at 10:08 PM, funth1ngs notifications@github.com wrote:

Hi Angel,

not related to this problem, but can you pls try if an Orbit waypoint works for you in the SIM? I'm currently trying this, but the radius is much larger then it should.

Cheers, Heiko

— You are receiving this because you commented. Reply to this email directly or view it on GitHub https://github.com/mpaperno/jMAVSim/issues/1#issuecomment-214030133

mpaperno commented 8 years ago

Heiko, which fw. are you running, the latest I posted here? As I mentioned, it's in the middle of a nav. module rework... I think it's mostly OK, but it's possible I broke something with the orbit wpt (or elsewhere). Though as I said, I haven't tried an orbit wpt in any recent version with or w/out the sim.

Angel, try a faster computer or running only the sim on the NUC. I think it's struggling with QGC and everything else running on there. As mentioned, the nav stuff seems to be the first thing to go, and there's no way to tune that out.

-Max

mpaperno commented 8 years ago

I'm going to mark this fixed/closed, though we can continue discussion here if we want. Or maybe take it to the forums or a new issue (for the nav stuff or other performance problems).

Thanks again to Heiko! :+1:

Fixed by 5babbe3.

-Max

h3ifri commented 8 years ago

Hi Max!

Heiko, which fw. are you running. As I mentioned, it's in the middle of a nav. module rework...

Oh, I had already forgotten about that, used the one you posted here... This could also explains why I saw something like a spline ;) Anyway, looking forward to try it out.

I'd like to thank you once again for the great work and effort you put in the AQ project, I really appricate it a lot. I'm glad to help whenever I can.

Cheers, Heiko

afernan commented 8 years ago

Max:

Did you open any other discussion for other HIL issues?

Meanwhile, I´ve tested HIL with my I7 machine with same behaviour of that of NUC-I5, so in PH doing circles. CPU is very low loaded (<20%)

Similar hapened to me also in ARDUCOPTER Project while HIL testing (long time ago) and in real Arducopter due to lag time between GPS data and CPU processing corrections. We could have a similar case here if the loop CPU vs GPS generated by jSIM is not quick enough. Just an idea

Angel

On Mon, Apr 25, 2016 at 11:24 AM, funth1ngs notifications@github.com wrote:

Hi Max!

Heiko, which fw. are you running. As I mentioned, it's in the middle of a nav. module rework...

Oh, I had already forgotten about that, used the one you posted here... This could also explains why I saw something like a spline ;) Anyway, looking forward to try it out.

I'd like to thank you once again for the great work and effort you put in the AQ project, I really appricate it a lot. I'm glad to help whenever I can.

Cheers, Heiko

— You are receiving this because you commented. Reply to this email directly or view it on GitHub https://github.com/mpaperno/jMAVSim/issues/1#issuecomment-214228430