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

MavSDK-JAVA v2.0.1, INVALID_SEQUENCE for uploading mission with MissionRaw -- Kotlin Android #182

Open
Ba0Nguyen opened this issue Sep 27, 2024 · 24 comments

Comments

@Ba0Nguyen
Copy link

Ba0Nguyen commented Sep 27, 2024

I am unable to upload a mission using MissionRaw. My mission have multiple MissionRaw.MissionItem, sample code below:

`
private fun createMissionPlan(): List<MissionRaw.MissionItem> {

val missionRawItems = mutableListOf<MissionRaw.MissionItem>()

// Set Home Point
missionRawItems.add(createMissionItemRaw(0, 1, 16, 1, 1,0f, 0f, 0f, 0f,0f, 0f,548.6f, 0))

// Take off
missionRawItems.add(createMissionItemRaw(1, 0, 22, 0, 1,0f, 0f, 0f, 0f,0f, 0f, altitudeM.toFloat(), 0))

// add two waypoints
missionRawItems.add(createMissionItemRaw(2, 0, 16, 0, 1,0f, 0f, 0f, 0f, latitude, longitude, altitude, 0))
missionRawItems.add(createMissionItemRaw(3, 0, 16, 0, 1,0f, 0f, 0f, 0f, latitude, longitude, altitude, 0))

return missionRawItems
}

private fun createMissionItemRaw(seq: Int, frame: Int, command: Int, current: Int, autocontinue: Int,
param1: Float, param2: Float, param3: Float, param4: Float,
x: Float, y: Float, z: Float, missionType: Int): MissionRaw.MissionItem {

    val missionItem = MissionRaw.MissionItem(seq, frame, command, current, autocontinue,
        param1, param2, param3, param4,
        (x * 1e7).roundToInt(), (y * 1e7).roundToInt(), z, missionType)

    return missionItem
}

`

I am able to upload the mission successfully with just only one MissionItem (e.g. home point). Whenever I try to add a mission with two MissionItems or more, I got Invalid_Sequence even thought my sequence number is correctly increment from 0.

Thanks for your help!

@Ba0Nguyen Ba0Nguyen changed the title MavSDK-JAVA v2.0.0, INVALID_SEQUENCE for uploading mission with MissionRaw MavSDK-JAVA v2.0.0, INVALID_SEQUENCE for uploading mission with MissionRaw -- Kotlin Android Sep 27, 2024
@julianoes
Copy link
Contributor

Is this against PX4 or ArduPilot?

Can you make sure that Current is 0 for the 0th item, and 1 for the first one?

Also see this thread: mavlink/MAVSDK#2058

@Ba0Nguyen
Copy link
Author

Ba0Nguyen commented Sep 30, 2024

This is against Ardupilot v4.4.4.

I will try setting the current 0 for the 0th item, and when you mention current 1 for the 'first one'. Did you meant the TAKE_OFF message or the First WayPoint?

Do you think it could be that MavSDK did not send the Total Count (MISSION_COUNT) for waypoint?

Referencing "Upload a Mission to the Vehicle".
https://mavlink.io/en/services/mission.html

@Ba0Nguyen
Copy link
Author

Ba0Nguyen commented Sep 30, 2024

    `// set home position
    missionRawItems.add(createMissionItemRaw(0, 5, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473977420f, 85455939f,488.7872009277344f, 0))
    // set take off
    missionRawItems.add(createMissionItemRaw(0, 3, 22, 0, 1,
        0f, 0f, 0f, 0f,
        473977420f, 85455939f, 50f, 0))
    
    // set waypoints
    missionRawItems.add(createMissionItemRaw(1, 3, 16, 1, 1,
        0f, 0f, 0f, 0f,
        waypoints[5].latitude.toFloat(),  waypoints[5].longitude.toFloat(), altitudeM.toFloat(), 0))

    missionRawItems.add(createMissionItemRaw(2, 3, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473982493f, 85449242f,50f, 0))

    missionRawItems.add(createMissionItemRaw(3, 3, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473977416f,85449242f, 50f, 0))

    missionRawItems.add(createMissionItemRaw(4, 2, 20, 0, 1,
        0f, 0f, 0f, 0f,
        0f, 0f, 0f, 0))`
        
        I tried this and got "Invalid Sequence INVALID_SEQUENCE"

@Ba0Nguyen
Copy link
Author

    `// set home position
    missionRawItems.add(createMissionItemRaw(0, 5, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473977420f, 85455939f,488.7872009277344f, 0))
    // set take off
    missionRawItems.add(createMissionItemRaw(0, 3, 22, 1, 1,
        0f, 0f, 0f, 0f,
        473977420f, 85455939f, 50f, 0))

    // set waypoints
    missionRawItems.add(createMissionItemRaw(1, 3, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473982266f, 85455604f, 50f, 0))

    missionRawItems.add(createMissionItemRaw(2, 3, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473982493f, 85449242f,50f, 0))

    missionRawItems.add(createMissionItemRaw(3, 3, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473977416f,85449242f, 50f, 0))

    missionRawItems.add(createMissionItemRaw(4, 2, 20, 0, 1,
        0f, 0f, 0f, 0f,
        0f, 0f, 0f, 0))`

I also tried the above and got Invalid Sequence INVALID_SEQUENCE

@julianoes
Copy link
Contributor

Do you think it could be that MavSDK did not send the Total Count (MISSION_COUNT) for waypoint?

I don't think so. I assume you're hitting this one:
https://github.com/mavlink/MAVSDK/blob/0b564f0deef4d6a67e6b542ec10c59cc0b33f482/src/mavsdk/core/mavlink_mission_transfer_client.cpp#L228-L234

The sequence should be 0, 1, 2, 3, not 0, 0, 1, 2, 3, pretty sure.

@Ba0Nguyen
Copy link
Author

Ba0Nguyen commented Sep 30, 2024

I also tried 0,1,2,3,4 sequence and got INVALID_ARGUMENT.

    `// set home position
    missionRawItems.add(createMissionItemRaw(0, 0, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473977420f, 85455939f,0f, 0))
    // set take off
    missionRawItems.add(createMissionItemRaw(1, 3, 22,  1, 1,
        0f, 0f, 0f, 0f,
        473977420f, 85455939f, 50f, 0))

    // set waypoints
    missionRawItems.add(createMissionItemRaw(2, 3, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473982266f, 85455604f, 50f, 0))

    missionRawItems.add(createMissionItemRaw(3, 3, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473982493f, 85449242f,50f, 0))

    missionRawItems.add(createMissionItemRaw(4, 3, 16, 0, 1,
        0f, 0f, 0f, 0f,
        473977416f,85449242f, 50f, 0))
    missionRawItems.add(createMissionItemRaw(5, 2, 20, 0, 1,
        0f, 0f, 0f, 0f,
        0f, 0f, 0f, 0))`

@Ba0Nguyen
Copy link
Author

I am logging out messages MavSDK is receiving from Ardupilot. What I notice is I only received MISSION_REQUEST_INT for 0, which explain why I was able to upload mission with 1 Mission Item successfully. I've never receive MISSION_REQUEST_INT for 1 and failed to upload mission with 2 or more Mission Items.

@Ba0Nguyen
Copy link
Author

Ba0Nguyen commented Sep 30, 2024

Do you think this might potentially giving us problem?

mavlink_mission_transfer_client.cpp

   ` // ArduCopter 3.6 sends MISSION_REQUEST (not _INT) but actually accepts ITEM_INT in reply

    // FIXME: this will mess with the sequence number.
    mavlink_message_t request_int_message;
    mavlink_msg_mission_request_int_pack(
        request_message.sysid,
        request_message.compid,
        &request_int_message,
        request.target_system,
        request.target_component,
        request.seq,
        request.mission_type);`

@julianoes
Copy link
Contributor

Can you provide an example, or add a mission example to the example app? That way I can easily try to reproduce this issue.

@Ba0Nguyen
Copy link
Author

Ba0Nguyen commented Oct 1, 2024

private fun uploadMission(missionRaw: MissionRaw) {
        val missionCoordinates = listOf(
            Coordinate(id = "0", latitude = 40.4093871, longitude = -3.6904990),
            Coordinate(id = "1", latitude = 40.4088917, longitude = -3.6896253),
            Coordinate(id = "2", latitude = 40.4083849, longitude = -3.6901396),
            Coordinate(id = "3", latitude = 40.4089193, longitude = -3.6909593),
        )

        val missionPlan: MutableList<MissionRaw.MissionItem> = mutableListOf()
        val homeMissionItem = createMissionItemRaw(0, 0, 16, 1, 1,
            0f, 0f, 0f, 0f,
            40.4093928f, -3.6903115f,0f, 0)

        val takeoff = createMissionItemRaw(1, 3, 22,  0, 1,
            0f, 0f, 0f, 0f,
            0f, 0f, 50f, 0)

        missionPlan.add(homeMissionItem)
        missionPlan.add(takeoff)

        var seq = missionPlan.size // size = 2
        for (coordinate in missionCoordinates) {
            val missionItem = createMissionItemRaw(
                seq = seq,
                frame = 3,
                command = 22,
                current = 0,
                autocontinue = 1,
                0f,0f,0f,0f,
                x = coordinate.latitude.toFloat(),
                y = coordinate.longitude.toFloat(),
                z = 100f,
                missionType = 0)
            missionPlan.add(missionItem)
            seq++
        }

        CoroutineScope(Dispatchers.IO).launch {
            val completable = missionRaw.uploadMission(missionPlan)
            completable
                .doOnComplete { Log.d("UploadingMission", "Upload mission completed") }
                .doOnError { e -> Log.d("UploadingMission", "ERROR: ${e.message} ${e.cause}") }
                .subscribe()
        }
    }

    private fun createMissionItemRaw(seq: Int, frame: Int, command: Int, current: Int, autocontinue: Int,
                                     param1: Float, param2: Float, param3: Float, param4: Float,
                                     x: Float, y: Float, z: Float, missionType: Int): MissionRaw.MissionItem {

        val missionItem = MissionRaw.MissionItem(seq, frame, command, current, autocontinue,
            param1, param2, param3, param4,
            (x * 1e7).roundToInt(), (y * 1e7).roundToInt(), z, missionType)
        return missionItem
    }

@Ba0Nguyen
Copy link
Author

I got this as result "ERROR: INVALID_SEQUENCE: Invalid Sequence null" for the above code.

@julianoes
Copy link
Contributor

julianoes commented Oct 1, 2024

What does this do?

        var seq = missionPlan.size // size = 2

Oh nevermind, got it.

@julianoes
Copy link
Contributor

You write v2.0.0 but that version doesn't exist, so what version exactly are you using?

@Ba0Nguyen
Copy link
Author

Sorry, I meant v2.0.1

@Ba0Nguyen Ba0Nguyen changed the title MavSDK-JAVA v2.0.0, INVALID_SEQUENCE for uploading mission with MissionRaw -- Kotlin Android MavSDK-JAVA v2.0.1, INVALID_SEQUENCE for uploading mission with MissionRaw -- Kotlin Android Oct 1, 2024
@julianoes
Copy link
Contributor

v2.1.0 maybe?
https://github.com/mavlink/MAVSDK-Java/releases

@Ba0Nguyen
Copy link
Author

To clarify:

MAVSDK-JAVA (I pulled from the main branch in May, so it wasn't an official release yet)

  • mavsdk-server: v2.1.0
  • sdk: v2.0.1

@Ba0Nguyen
Copy link
Author

While debugging, I noticed that the unregister_all function in the MavlinkMessageHandler class (in MAVSDK C++) is called when I try to upload the mission to the drone flight controller. This did not happen with the simulator and I was able to upload the flight plan successfully.

@julianoes
Copy link
Contributor

Hm, so this issue still persists for SITL then?

@Ba0Nguyen
Copy link
Author

It is working when I upload mission to SITL.

@julianoes
Copy link
Contributor

Nice ok, so I can close this.

@Ba0Nguyen
Copy link
Author

To clarify :

It is always working with SITL but I've never get a mission to upload successfully on the actually Flight Controller with Ardupilot v4.4.4. I always got INVALID_SEQUENCE when try to upload to the actual Flight Controller.

@julianoes julianoes reopened this Oct 7, 2024
@julianoes
Copy link
Contributor

Ok, I understand, so this stays open and I need to try to reproduce it.

@Ba0Nguyen
Copy link
Author

Were you able to reproduce the issue?

@julianoes
Copy link
Contributor

Not yet, thanks for the reminder. Easiest would be if you can make a branch of the example app that shows it.

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

No branches or pull requests

2 participants