Page 1 of 1

[Solved] Simple Hover program

Posted: Mon May 19, 2014 11:11 pm
by crazydontflie
Hi all,

I made a very simple python program that simply turns on thrust to get the crazyflie in the air, and then uses the hover functionality to enable hover mode. I looked extensively at the way hover was implemented in cfclient source code, and attempted to mimic this functionality. The hover is set as such:

Code: Select all

cf.param.set_value("flightmode.althold", "True")
However, the hover mode appears to be set for about half a second, then turns off. Below is the entire source for setting hover mode:

Code: Select all

import sys
sys.path.append("../lib")

import cflib.crtp
import time
from cflib.crazyflie import Crazyflie

# Initialize the low-level drivers (don't list the debug drivers)
cflib.crtp.init_drivers(enable_debug_driver=False)

print "Scanning interfaces for Crazyflies..."
available = cflib.crtp.scan_interfaces()
print "Crazyflies found:"
for i in available:
    print i[0]

if len(available) > 0:
    # Create a Crazyflie object without specifying any cache dirs
    cf = Crazyflie()

    def handle_connected(link_uri):
        print "Connected to %s" % link_uri

        print "Sending thrust 45000"
        cf.commander.send_setpoint(0, 0, 0, 45000)
        time.sleep(0.75)

        print "Stopping thrust; hovering"
        cf.commander.send_setpoint(0, 0, 0, 0)
        cf.param.set_value("flightmode.althold", "True")

    def close_link():
        print 'Closing'
        cf.commander.send_setpoint(0, 0, 0, 0)
        time.sleep(0.1)
        cf.close_link()

    # Connect some callbacks from the Crazyflie API
    cf.connected.add_callback(handle_connected)

    link_uri = available[0][0]
    print "Connecting to %s" % link_uri

    # Try to connect to the Crazyflie
    cf.open_link(link_uri)

    # Variable used to keep main loop occupied until disconnect
    is_connected = True

    try:
        while True:
            time.sleep(1)
    except KeyboardInterrupt:
        close_link()
else:
    print "No Crazyflies found, cannot run example"
In a different program, I printed out data from the altHold target, and observed the values. It appears that upon first setting hover mode, it works for the first half second or so, but soon it turns off, as seen in the logging debugging printout below.

Code: Select all

[957179][Stabilizer]: {'altHold.target': 33.872318267822266, 'altHold.err': 0.1075897216796875}
[957279][Stabilizer]: {'altHold.target': 33.82230758666992, 'altHold.err': 0.11747360229492188}
[957379][Stabilizer]: {'altHold.target': 33.77229690551758, 'altHold.err': 0.11321258544921875}
[957579][Stabilizer]: {'altHold.target': 33.67227554321289, 'altHold.err': 0.3401451110839844}
[957679][Stabilizer]: {'altHold.target': 33.62226486206055, 'altHold.err': 0.3916740417480469}
[957779][Stabilizer]: {'altHold.target': 33.5722541809082, 'altHold.err': 0.3349266052246094}
[957879][Stabilizer]: {'altHold.target': 33.52224349975586, 'altHold.err': 0.3975334167480469}
[957979][Stabilizer]: {'altHold.target': 33.472232818603516, 'altHold.err': 0.43831634521484375}
[958179][Stabilizer]: {'altHold.target': 33.37221145629883, 'altHold.err': 0.5722694396972656}
[958279][Stabilizer]: {'altHold.target': 33.322200775146484, 'altHold.err': 0.6295738220214844}
[958379][Stabilizer]: {'altHold.target': 33.27219009399414, 'altHold.err': 0.6853408813476562}
[958479][Stabilizer]: {'altHold.target': 33.2221794128418, 'altHold.err': 0.699859619140625}
[958579][Stabilizer]: {'altHold.target': 33.17216873168945, 'altHold.err': 0.7846832275390625}
[958679][Stabilizer]: {'altHold.target': 33.12215805053711, 'altHold.err': 0.7600898742675781}
[958779][Stabilizer]: {'altHold.target': 33.072147369384766, 'altHold.err': 0.7624588012695312}
[958879][Stabilizer]: {'altHold.target': 33.02213668823242, 'altHold.err': 0.7686080932617188}
[958979][Stabilizer]: {'altHold.target': 32.97212600708008, 'altHold.err': 0.8769187927246094}
[959079][Stabilizer]: {'altHold.target': 32.922115325927734, 'altHold.err': 0.9493331909179688}
[959179][Stabilizer]: {'altHold.target': 0.0, 'altHold.err': 0.0}
[959279][Stabilizer]: {'altHold.target': 0.0, 'altHold.err': 0.0}
... etc.
Any ideas on why the hover mode is not working?

Thank you!

Re: Simple Hover program

Posted: Fri May 23, 2014 1:13 am
by crazydontflie
Bump. Can anyone provide any input? I have now tried many different things, including sending packets at 100Hz to ensure the copter doesn't time out, but that has not fixed the problem....

Re: Simple Hover program

Posted: Fri May 23, 2014 11:04 am
by omwdunkley
crazydontflie wrote:Bump. Can anyone provide any input? I have now tried many different things, including sending packets at 100Hz to ensure the copter doesn't time out, but that has not fixed the problem....
Hi, to be honest, I am not sure whats wrong :/ Code + sending commands packets looks okay to me. Maybe one of the moderators has an idea?

Re: Simple Hover program

Posted: Fri May 23, 2014 1:40 pm
by derf
Hi Oliver,

I'm currently doing some tests with setting parameters from a Java based Crazyflie lib and I noticed something similar to what "crazydontflie" reported.
If I set the "flightmode.althold" parameter to 1, it seems like the parameter resets itself after a very short time.
Right now, I don't know if I'm doing something wrong or if this is an intended behavior.
Maybe you can shed some light on this?

Regards,

Fred

Re: Simple Hover program

Posted: Fri May 23, 2014 2:14 pm
by omwdunkley
derf wrote:Hi Oliver,

I'm currently doing some tests with setting parameters from a Java based Crazyflie lib and I noticed something similar to what "crazydontflie" reported.
If I set the "flightmode.althold" parameter to 1, it seems like the parameter resets itself after a very short time.
Right now, I don't know if I'm doing something wrong or if this is an intended behavior.
Maybe you can shed some light on this?

Regards,

Fred
Hey Fred,

sorry I have not really got time to debug this in the next weeks..but thanks for narrowing down the problem.
Does it work with the stock client and stock firmware?

Re: Simple Hover program

Posted: Mon May 26, 2014 11:20 pm
by derf
Hi Oliver,

Tried it with the latest Python client (cfclient-2014.01.0) and the latest firmware (Crazyflie_2014.01.0.bin) and found the same behavior.
When I go to the parameters tab and change the value of flightmode.althold from 0 to 1, the rotors spin for a second, then stop. At the same time the value changes back to 0.
Changing other values (e.g. altHold.maxThrust from 60000 to 50000) works as expected (value does not reset to the original value).

The automatic reset of the flightmode.althold parameter feels almost like a security feature, because you can't get stuck in the altitude hold mode (which can be a good thing). :)
If it's actually a feature, it just needs to be documented to avoid confusion.

Apart from that odd parameter behavior, altitude hold works as expected with the Python client.

Regards,

Fred

Re: Simple Hover program

Posted: Mon May 26, 2014 11:51 pm
by crazydontflie
Hey all,

I was able to fix the problem by more carefully studying the python client - when altitude hold is enabled, I had to send packets with a 32767 thrust value at regular interval (100hz worked fine for me). For some reason, sending a thrust of 0 did not work but 32767 did. Now everything works.

Re: Simple Hover program

Posted: Tue May 27, 2014 12:02 am
by omwdunkley
crazydontflie wrote:Hey all,

I was able to fix the problem by more carefully studying the python client - when altitude hold is enabled, I had to send packets with a 32767 thrust value at regular interval (100hz worked fine for me). For some reason, sending a thrust of 0 did not work but 32767 did. Now everything works.
Nice one :) I guess I should have thought of that, sorry!
Usually the thrust is just mapped 0->+1 : 10000->60000 (with a reserve ~5000 left for the flie to stabilize).
When in hover mode the thrust is used to change the target altitude. As we are using the same uint16 to transport the signal we now map -1->+1 : 0:65000, where 32767 the corresponds to 0, the middle (so no change to the altitude goal).

The target altitude can be logged in the althold group!

Not sure why this causes the parameter goes back to 0 though...

Re: Simple Hover program

Posted: Tue May 27, 2014 11:28 pm
by derf
Thanks crazydontflie for finding that out! :)

Re: [Solved] Simple Hover program

Posted: Tue Aug 12, 2014 12:03 pm
by erlingrj
I don't quite understand how you solved the problem. I am able to access alt_hold with my PS3 controller and it works quite well, but writing the code cf.param.set_value("flightmode.althold","True") does nothing. Did you enable althold and afterwords start sending packets with that thrust equal 32767 like:

Code: Select all

cf.commander.send_setpoint(0,0,0,initial_thrust);
time.sleep(0.5);

cf.param.set_value("flightmode.althold","True");

while some_condition:
     cf.commander.send_setpoint(0,0,0,32767);
     time.sleep(0.01);

Because this does not enable the althold-mode for me!