dronekit / dronekit-python

DroneKit-Python library for communicating with Drones via MAVLink.
https://readthedocs.org/projects/dronekit-python/
Apache License 2.0
1.62k stars 1.45k forks source link

goto should probably be a SET_POSITION_TARGET_GLOBAL_INT command #165

Open hamishwillee opened 9 years ago

hamishwillee commented 9 years ago

The implementation of goto is a bit odd - for a start it is called as part of vehicle.commands.goto, while commands is normally for missions? Anyway, the implementation currently uses mission_item_encode. My understanding is that this is for encoding mission items to be handled in missions. For "Guided" commands it should use SET_POSITION_TARGET_GLOBAL_INT.

The code would look something like this (taken from the example code added in #170):

def goto_position_target_global_int(aLocation):
    """
    Send SET_POSITION_TARGET_GLOBAL_INT command to request the vehicle fly to a specified location.

    For more information see: https://pixhawk.ethz.ch/mavlink/#SET_POSITION_TARGET_GLOBAL_INT

    See the above link for information on the type_mask (0=enable, 1=ignore). 
    At time of writing, acceleration and yaw bits are ignored.
    """
    print 'goto_target_globalint_position'
    msg = vehicle.message_factory.set_position_target_global_int_encode(
        0,       # time_boot_ms (not used)
        0, 0,    # target system, target component
        mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, # frame      
        0b0000111111111000, # type_mask (only speeds enabled)
        aLocation.lat*1e7, # lat_int - X Position in WGS84 frame in 1e7 * meters
        aLocation.lon*1e7, # lon_int - Y Position in WGS84 frame in 1e7 * meters
        aLocation.alt, # alt - Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
        0, # X velocity in NED frame in m/s
        0, # Y velocity in NED frame in m/s
        0, # Z velocity in NED frame in m/s
        0, 0, 0, # afx, afy, afz acceleration (not supported yet, ignored in GCS_Mavlink)
        0, 0)    # yaw, yaw_rate (not supported yet, ignored in GCS_Mavlink) 
    # send command to vehicle
    vehicle.send_mavlink(msg)
    vehicle.flush()
tcr3dr commented 9 years ago

This should land in DKPY2. I'm going to pull in @wsilva32 and @eliao in here for this, since .goto is the only commands mechanism used by Solo rn.

If a vehicle.goto method existed, would implementing it like the above be suitable? Versus our current implementation.

wsilva32 commented 9 years ago

That should be fine. For classic cable/selfie we use the vehicle.commands.goto() function in combination with a MAV_CMD_DO_SPEED to head to one point or another. We are slowly phasing this type of control out in favor of using a more explicit control interface, such as:

self.vehicle.message_factory.set_position_target_global_int_encode( 0, # time_boot_ms (not used) 0, 1, # target system, target component mavutil.mavlink.MAV_FRAME_GLOBAL, # frame 0b0000110111000000, # type_mask - enable pos/vel int(newLoc.lat * 10000000), # latitude (degrees_1.0e7) int(newLoc.lon * 10000000), # longitude (degrees_1.0e7) newLoc.alt, # altitude (meters) newVel.x, newVel.y, -newVel.z, # North, East, Down velocity (m/s) 0, 0, 0, # x, y, z acceleration (not used) 0, 0) # yaw, yaw_rate (not used)

and plans to use the acceleration vector in the near future.

hamishwillee commented 9 years ago

@wsilva32 @tcr3dr So in effect you're slowly stopping using the things that make DroneKit worthwhile in favour of directly calling messages. Seems like a hint that we're doing things wrong in droneki?

Essentially we'll be calling your above function with position information. The only way in which I see this as more useful is if you're flying plane, where the frame isn't always global-relative as goto expects. What this method does allow that goto does not is direct control over the velocity components - something I'd like to see.

Can you explain what DK might/should do that this does better?

eliao commented 9 years ago

@hamishwillee

ArduCopter has several controllers.

One is the position controller, which goto uses. This is not appropriate for many of our shots.

Another one is the velocity controller, which takes input velocities. And finally, we have the pos-vel controller, which takes both positions and velocities. We would need Dronekit to expose these in order for the shots to use them. So I could imagine DroneKit functions like: setVel() - for velocity controller setPosVel() - for pos-vel controller

And then in the future: setAccel() - for acceleration controller

(There are plenty of other things Dronekit could do to better serve the shots code; but we have just not been able to focus on them yet.)

hamishwillee commented 9 years ago

@eliao Thank you. We should discuss this and define an API - the direct commands are pretty ugly - especially with the bitmask for specifying which parameters are used in the move command. I didn't know you could set both position and velocity - is that just be setting the bitmask appropriately?

wsilva32 commented 9 years ago

@hamishwillee That's correct, the bitmask defines which ArduCopter controller is invoked by the set_position_target_global_int_encode command.

hamishwillee commented 9 years ago

@wsilva32 Thanks. Nice to be able to control the speed to get to a point in one go. Would actually be nice to add speed to the goto command.

We need to make DK-Python great for solo "first" - thats how I understand our mandate anyway.

tcr3dr commented 9 years ago

Fortuitously, I don't think we need this to block the DKPY2 release because it our current methods are in the wrong namespace—vehicle.goto can be logically distinct, so it won't break backcompat (vehicle.commands.goto can just be deprecated). Given this, I'm reclassifying this as an enhancement and removing it from DKPY2 blockers.

Doesn't mean we won't get to it soon, but I do want to move ahead with a proper release.

hamishwillee commented 9 years ago

OK by me. Lots more thinking needs to be done around supporting movement by position and velocity (local and global and relative to the vehicle body/heading)