jaspreeth / ardupilot-mega

Automatically exported from code.google.com/p/ardupilot-mega
0 stars 0 forks source link

CONDITION_CHANGE_ALT only works for ascending. #438

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
What steps will reproduce the problem?

#define WP_RADIUS 30 // What is the minimum distance to reach a waypoint?
#define LOITER_RADIUS 60        // How close to Loiter?
#define HOLD_CURRENT_ALT 0      // 1 = hold the current altitude, 0 = use the 
defined altitude to for RTL
#define ALT_TO_HOLD 100
float mission[][5] = {

{WAYPOINT,0,528,49.9630094,-119.378643},
{LOITER_TURNS,1,1500,49.963037,-119.3742228},
{CONDITION_CHANGE_ALT,0,1500,1000,0},
{DO_JUMP,7,0,49,0},
{LOITER_TIME,5,1500,49.963037,-119.3730211},
{DO_JUMP,2,0,100,0},

{WAYPOINT,0,1500,49.9585921,-119.3729353},
{LOITER_TURNS,1,1500,49.9585921,-119.3743086},
{CONDITION_CHANGE_ALT,0,528,1000,0},
{DO_JUMP,13,0,49,0},
{LOITER_TIME,5,528,49.9585645,-119.3757248},
{DO_JUMP,8,0,49,0},

{WAYPOINT,0,528,49.9583989,-119.3808317},
{RETURN_TO_LAUNCH,0,528,49.9629542,-119.3808746},
};

What is the expected output? What do you see instead?

Plane loiters to high altitude, goes to next waypoint, than descends and 
continues to next waypoint. Everything works except the descending part.

What version of the product are you using? On what operating system?

Arduplane 2.24.

Please provide any additional information below.

Original issue reported on code.google.com by mike.ben...@gmail.com on 8 Nov 2011 at 3:16

Attachments:

GoogleCodeExporter commented 8 years ago
hi mike,

in order to descend you have to change the sign to the altitude rate. I had the 
problem during hil simulation ;-)

Original comment by cosimo.m...@gmail.com on 10 Nov 2011 at 4:05

GoogleCodeExporter commented 8 years ago
So you mean instead of:

{CONDITION_CHANGE_ALT,0,528,1000,0},

Use:

{CONDITION_CHANGE_ALT,0,-528,1000,0},

That still seems like a bug to me. CONDITION_CHANGE_ALT should be the same as 
other way points, which you would never use a negative value for.

Original comment by mike.ben...@gmail.com on 10 Nov 2011 at 5:10

GoogleCodeExporter commented 8 years ago
sorry, I wasn't so clear. I mean:

if you have to "increase" the altitude to 528 m the sign of "rate" have to be 
positive:
{CONDITION_CHANGE_ALT,0,528,1000,0}

if you want to "decrease" the altitude to 528 m the sign of "rate" have to be 
negative:
{CONDITION_CHANGE_ALT,0,528,-1000,0}

Original comment by cosimo.m...@gmail.com on 10 Nov 2011 at 8:44

GoogleCodeExporter commented 8 years ago
Okay, that may be a workaround for now, but even that seems like it would still 
be a bug. 

Ardupilot should be smart enough to know if the altitude is causing it to 
ascend or descend and use the rate appropriately without requiring a human to 
explicitly tell it "up" or "down" with a signed rate value.

What happens if the plane is at 1000m and the command is:
 {CONDITION_CHANGE_ALT,0,1500,-1000,0}

Does the plane descend until it crashes because the rate says -1000 and it will 
never reach the higher target altitude?

Original comment by mike.ben...@gmail.com on 10 Nov 2011 at 10:14

GoogleCodeExporter commented 8 years ago
I had exatly this problem during hil simulation and also the problem related to 
relative/absolute altitude reported in the previous issue (437). The two 
problems should be solved asap !!

Original comment by cosimo.m...@gmail.com on 11 Nov 2011 at 5:52

GoogleCodeExporter commented 8 years ago
A bug fix has been pushed to the trunk so that you no longer need to use a 
signed rate.  The code will determine if a positive or negative rate is 
required and act accordingly.

Original comment by dewei...@gmail.com on 9 Jan 2012 at 1:26