Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: First take on takeoff script #19

Open
wants to merge 10 commits into
base: skyviper-latest
Choose a base branch
from

Conversation

iamczar
Copy link
Contributor

@iamczar iamczar commented Oct 20, 2017

Hi Peter or Tridge

I think one of my task for next years features are to implement a takeoff cmd assigned to a button.
Could you please review my first take on my takeoff cmd script?

At the moment I have assigned it to the right action button (photo btn).

I have tested it only indoors.

To test this PR.
1.power cycle the copter and tx
2.pair the copter and tx
3.press photo button

Thank you

@peterbarker
Copy link
Contributor

Before I look closely at this PR - have you reviewed ArduCopter's pre-existing take-off code?

It was added for the 3DR Solo vehicle, and is currently in use on it. This is the start of relevant code in alt-hold mode: https://github.com/ardupilot/ardupilot/blob/master/ArduCopter/control_althold.cpp#L92

@iamczar
Copy link
Contributor Author

iamczar commented Oct 23, 2017

No I haven't. I shall look into it. Tridge mention that we should do it in toy_mode.cpp as there is already a throttle_control.

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I will need to stare at this state machine a lot after these changes are made.

I've a feeling we can get into funny states ATM.

Also, watch out for whitespace issues. There's trailing whitespace added in this patch (ask your editor to highlight it). You're missing the odd space here and there between closing prens and opening braces (if (foo){).

@@ -405,6 +405,9 @@ void ToyMode::update()
} else {
throttle_low_counter = 0;
}

bool takeoff_cancelled = throttle_at_min || throttle_near_max;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

const takeoff_cancelled

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why cancel takeoff if the throttle is near max? Is this so people can takeoff conventionally after pressing the button?

If I'm asking the question it probably deserves a comment :-)

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could probably just use outside-deadzone instead.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This check should probably move into the subroutine.

@@ -405,6 +405,9 @@ void ToyMode::update()
} else {
throttle_low_counter = 0;
}

bool takeoff_cancelled = throttle_at_min || throttle_near_max;
handle_takeoff_cmd(right_action_button,takeoff_cancelled);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should be checking for a specific toy_mode_action, not checking whether the right button has been pressed.

So something like an ACTION_TAKEOFF_OR_CANCEL_TAKEOFF_OR_RTL

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Speaking of which, the button should cancel the takeoff if pressed a second time while it is still on the ground (IMO), like the current arm/disarm/rtl functionality does.

Also, need the RTL functionality....

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, - in our next years drone. on the TX for copters that has GPS there is a button to toggle between launch and land and a separate button for RTL.

I was thinking maybe do this - ACTION_TAKEOFF_CANCEL_TAKEOFF_LAND instead.

@@ -818,6 +821,19 @@ void ToyMode::throttle_adjust(float &throttle_control)
float p = (now - throttle_arm_ms) / float(soft_start_ms);
throttle_control = MIN(throttle_control, throttle_start + p * (1000 - throttle_start));
}

//takeoff script to handle the throttle_control. takeoff_cmd is handled by handle_takeoff_cmd()
const float takeoff_throttle_cmd = 700.0f;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, I'm not a great fan of having relying on a timer with a constant like this. I think frame variations (bodgy motors) and environmental conditions (wind!) could lead to some unfortunate flight characteristics.

However, the current ArduCopter takeoff code relies on a good sense of the vehicle's altitude, and it is unclear as to whether we will have that on vehicles on their first flight.

Given that, this arrangement is probably required on the current SkyViper hardware.

One alternative would be to use the current ArduCopter takeoff code but capping the time allowed for it to run. This would prevent the vehicle hitting the ceiling inside while using a more elaborate and flexible (but pre-existing!) control mechanism for the takeoff. I only mention this as an alternative in case the current code doesn't work across many frames.


//takeoff script to handle the throttle_control. takeoff_cmd is handled by handle_takeoff_cmd()
const float takeoff_throttle_cmd = 700.0f;
const uint32_t takeoff_time_ms = 1500;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

uint16_t? :)

if(now - takeoff_arm_ms < takeoff_time_ms){
throttle_control = takeoff_throttle_cmd;
} else {
takeoff_state = TAKEOFF_IN_AIR;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Quite an assumption. Maybe TAKEOFF_TIMER_FINISHED?

}
}
break;
case TAKEOFF_ARMED:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Possibly rename state to something describing what's being attempted in this state - TAKEOFF_DO_ASCEND or TAKEOFF_DO_CLIMB?

//ability to cancel takeoff cmd during take off
if ((takeoff_cmd && takeoff_cancel)) {

if(takeoff_cmd){
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

redundant check

@@ -97,6 +99,13 @@ class ToyMode
BLINK_VSLOW = 0xF000,
BLINK_MED_1 = 0xF0F0,
};

enum takeoff_states {
TAKEOFF_ON_GROUND = 0,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe TAKEOFF_INACTIVE. You may be on the ground and spinning props menacingly.



//used for takeoff cmd
uint8_t takeoff_cmd;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Use a struct to hold these. e.g.

struct {
    uint8_t state;
    uint32_t arm_ms;
    uint32_t last_press_ms;
} takeoff;

Then reference with `takeoff.arm_ms`

//used for takeoff cmd
uint8_t takeoff_cmd;
uint8_t takeoff_state;
int32_t takeoff_arm_ms;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

uint32_t

@tridge
Copy link
Contributor

tridge commented Nov 4, 2017

hi Czar,
I've done some work on this here:
https://github.com/tridge/ardupilot/tree/czar-launch-cmd
it simplifies the logic a bit, and makes the takeoff action assignable to a button. I think the intention is for it to be on the right face button? I've assumed that and made it a TAKEOFF_LAND_RTL action.
It seems to work nicely except that the first takeoff after booting doesn't takeoff. I have yet to work out why.
Can you take a look and see if you are ok with the approach I've taken?

@iamczar
Copy link
Contributor Author

iamczar commented Nov 6, 2017

Hi @tridge @peterbarker, for the next years drone I saw on the TX that there will be launch/land button and a separate button for rtl. Should the launch/land button also do RTL if you're in loiter? - https://drive.google.com/open?id=0B0qjKcHMJVP9SWFvSEVzU2t6OW8

@iamczar
Copy link
Contributor Author

iamczar commented Nov 8, 2017

Hi @peterbarker @tridge I added a 3 second delay before the throttle is applied. @peterbarker mentioned something about this line of code where some things do not get initialised when the copter is in ALT_HOLD
https://github.com/SkyRocketToys/ardupilot/blob/czar-launch-cmd/ArduCopter/toy_mode.cpp#L200. I thought it will also be nice to spin the motors first before taking off.

@tridge
Copy link
Contributor

tridge commented Nov 9, 2017

3 seconds seems like a long time to wait. Does it feel slow to use this? Maybe 0.5s or 1s would be OK, but 3s seems too long to me.
We also need to find out from Zech if this takeoff functionality is planned for the existing skyviper-gps. If it is then we'll need to keep the RTL functionality on the button.

@iamczar
Copy link
Contributor Author

iamczar commented Nov 9, 2017

I'll change it to 1s and see. I will ask Zech if we want this take off cmd to be on the existing streaming GPS.

@iamczar
Copy link
Contributor Author

iamczar commented Nov 9, 2017

@tridge - The takeoff functionality is not planned for existing skyviper-gps.

I just wanted to be preemptive on my task. I saw I had two days to do it but didn't know when that two days will start. :)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants