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

Improve trigger control for survey applications #11878

Merged
merged 18 commits into from
Mar 14, 2020

Conversation

LorenzMeier
Copy link
Member

QGC enables the trigger now on entering and exiting each transect without impacting the flight controller.

Rebased version of this:

#7739

@LorenzMeier LorenzMeier requested a review from dagar April 20, 2019 08:02
@LorenzMeier LorenzMeier force-pushed the pr-survey-trigger-control-rebased branch from 71745a5 to 51cbe78 Compare April 20, 2019 08:22
@LorenzMeier LorenzMeier requested a review from bkueng April 20, 2019 08:24
@DonLakeFlyer
Copy link
Contributor

I tested using this QGC hacked branch which add condition gate logic to surveys: https://github.com/DonLakeFlyer/qgroundcontrol/tree/ConditionGateHack and the attached plan file.

ConditionGate.plan.txt

This is a simple survey with a single transect. The new code will add the following at the end of transect survey edge:

  • CONDITION_GATE
  • TRIGGER_DISTANCE stop
  • Single CAMERA_TRIGGER
  • WAYPOINT for survey edge
  • WAYPOINT to turnaround point

When I tested the vehicle flew to the gate and just stopped there. At that point I think it was stuck at the gate command. The single image capture did not fire. So I don't think it ever moved past that.

@LorenzMeier
Copy link
Member Author

I need to build QGC and test end to end

@@ -86,6 +86,8 @@ param set MAV_SYS_ID $((px4_instance+1))
simulator_tcp_port=$((4560+px4_instance))
udp_offboard_port_local=$((14580+px4_instance))
udp_offboard_port_remote=$((14540+px4_instance))
udp_onboard_payload_port_local=$((14558+px4_instance))
Copy link
Contributor

Choose a reason for hiding this comment

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

14558 is not consistent with the other port numbers. However, we need to rethink these specs anyway.

Copy link
Member Author

Choose a reason for hiding this comment

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

@Jaeyoung-Lim What pattern do you recommend here?

Copy link
Contributor

Choose a reason for hiding this comment

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

Copy link
Member

Choose a reason for hiding this comment

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

This will conflict with udp_offboard_port_local after 22 instances. Would it be possible to find another slot? Regarding patterns I think the first port is defined up to the decimal, to be consistent with the others

Copy link
Member Author

Choose a reason for hiding this comment

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

which port do you suggest?

Copy link
Member

Choose a reason for hiding this comment

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

The used ports are only from 18570 +0~255 and 14580+0~255 so anything outside of this...so maybe 14280 would do the trick? Just a question, what is the downside of using the udp_offboard_port_local port for the onboard payload? This will only be used for development (SITL) and I cannot imagine too many people trying to use both at the sametime

Copy link
Member Author

Choose a reason for hiding this comment

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

The camera is a different component than actual off board == mission management interfaces. You can't mix them.

src/drivers/camera_trigger/camera_trigger.cpp Outdated Show resolved Hide resolved
src/drivers/camera_trigger/camera_trigger.cpp Outdated Show resolved Hide resolved
src/drivers/camera_trigger/camera_trigger.cpp Outdated Show resolved Hide resolved
src/drivers/camera_trigger/camera_trigger_params.c Outdated Show resolved Hide resolved
src/modules/navigator/mission_block.cpp Outdated Show resolved Hide resolved
src/modules/navigator/mission_block.cpp Outdated Show resolved Hide resolved
if (item.nav_cmd == NAV_CMD_DO_LAND_START) {
if (item_contains_position(item)
|| item_contains_gate(item)
|| item_contains_marker(item)) {
Copy link
Contributor

Choose a reason for hiding this comment

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

Nice!

src/modules/navigator/mission_block.h Outdated Show resolved Hide resolved
src/modules/navigator/mission_block.h Outdated Show resolved Hide resolved
@LorenzMeier
Copy link
Member Author

@DonLakeFlyer I will re-test with your QGC branch

@LorenzMeier
Copy link
Member Author

LorenzMeier commented May 5, 2019

@DonLakeFlyer I've tested with your QGC branch:

  • I ran QGC on this commit: DonLakeFlyer/qgroundcontrol@bac384a
  • I had to fix my test setup, it broke in the meantime, my bad. I've added a commit here on this PR now, you need to update and, you need to run SITL like this:
    make px4_sitl gazebo_plane_cam
  • I get this output from SITL in debug mode, so it seems to work:
[Msg] Took picture: frames/DSC00028.jpg
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 263 1 100 to: 127.0.0.1:14550
[Dbg] [gazebo_geotagged_images_plugin.cpp:262] Done with image capture
[Dbg] [gazebo_geotagged_images_plugin.cpp:569] Send capture status
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 262 1 100 to: 127.0.0.1:14550
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 0 1 100 to: 127.0.0.1:14550
[Dbg] [gazebo_geotagged_images_plugin.cpp:448] Handle Start Capture
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 77 1 100 to: 127.0.0.1:14558
[Msg] Took picture: frames/DSC00029.jpg
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 263 1 100 to: 127.0.0.1:14550
[Dbg] [gazebo_geotagged_images_plugin.cpp:262] Done with image capture
[Dbg] [gazebo_geotagged_images_plugin.cpp:569] Send capture status
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 262 1 100 to: 127.0.0.1:14550
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 0 1 100 to: 127.0.0.1:14550
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 0 1 100 to: 127.0.0.1:14550
[Dbg] [gazebo_geotagged_images_plugin.cpp:448] Handle Start Capture
[Dbg] [gazebo_geotagged_images_plugin.cpp:329] Message 77 1 100 to: 127.0.0.1:14558
  • I get the trigger messages in QGC, but they are not displayed on the map (which makes testing / debugging hard).

Could you look into this?

@DonLakeFlyer
Copy link
Contributor

@LorenzMeier error: unknown target 'gazebo_plane_cam', did you mean 'gazebo_plane_gdb'?

@LorenzMeier LorenzMeier force-pushed the pr-survey-trigger-control-rebased branch from 51cbe78 to 2fba83f Compare May 6, 2019 18:23
@LorenzMeier
Copy link
Member Author

Sorry, I pushed yesterday to the wrong branch name - fixed and pushed.

@DonLakeFlyer
Copy link
Contributor

When I do a Start Mission it always sends back Unable to start, vehicle not ready?

@LorenzMeier
Copy link
Member Author

You need a takeoff waypoint for a fixed wing

@Antiheavy
Copy link
Contributor

You need a takeoff waypoint for a fixed wing

there is even a (optional) check for that now! :) #11531

@DonLakeFlyer
Copy link
Contributor

You need a takeoff waypoint for a fixed wing

Not the problem. There is some sort of problem with either takeoff waypoint height or distance from home which ends up being reported as Unable to start instead of a better message. I'll try to get a repro.

@DonLakeFlyer
Copy link
Contributor

Screen Shot 2019-05-07 at 9 37 07 AM

Camera triggers have 0 lat/lon

@LorenzMeier LorenzMeier force-pushed the pr-survey-trigger-control-rebased branch from 2fba83f to d58f77a Compare May 18, 2019 08:27
@LorenzMeier
Copy link
Member Author

@DonLakeFlyer working on it.

Copy link
Contributor

@julianoes julianoes left a comment

Choose a reason for hiding this comment

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

Requesting changes so that my previous review doesn't get ignored and lost.

@stale
Copy link

stale bot commented Sep 11, 2019

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

@Antiheavy
Copy link
Contributor

Still relevant and needed! ;-)

@stale stale bot removed the Admin: Wont fix label Sep 11, 2019
@LorenzMeier LorenzMeier removed request for dagar and bkueng March 13, 2020 09:46
ROMFS/px4fmu_common/init.d-posix/1030_plane Outdated Show resolved Hide resolved
@@ -86,6 +86,8 @@ param set MAV_SYS_ID $((px4_instance+1))
simulator_tcp_port=$((4560+px4_instance))
udp_offboard_port_local=$((14580+px4_instance))
udp_offboard_port_remote=$((14540+px4_instance))
udp_onboard_payload_port_local=$((14558+px4_instance))
Copy link
Contributor

Choose a reason for hiding this comment

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


// Check that distance threshold is exceeded
if (matrix::Vector2f(_last_shoot_position - current_position).length() >= _distance) {
if (!_one_shot) {
Copy link
Contributor

Choose a reason for hiding this comment

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

I don't understand this _one_shot flag. Is this some sort of mode? And if so, is it orthogonal to _trigger_enabled?

Copy link
Member Author

Choose a reason for hiding this comment

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

It is orthogonal because it tells the system to take a single picture and disengage right after. If you wouldn't architect it this way you would need to schedule a HRT call to disengage the trigger right after, opening the door to horrible race conditions.

src/drivers/camera_trigger/camera_trigger.cpp Show resolved Hide resolved
src/modules/navigator/mission.cpp Show resolved Hide resolved
Comment on lines +1123 to +1128
// If the mission item under evaluation contains a gate,
// then we need to check if we have a next position item so
// the controller can fly the correct line between the
// current and next setpoint
if (item_contains_gate(_mission_item)) {
if (has_after_next_position_item) {
Copy link
Contributor

Choose a reason for hiding this comment

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

I'm trying to understand why this logic is needed twice 🤔.

Copy link
Member Author

Choose a reason for hiding this comment

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

I didn't want to refactor it in parallel, but basically one area is concerned with current waypoints and the one with next. This whole function needs to be broken down accordingly to make it readable again.

Copy link
Contributor

Choose a reason for hiding this comment

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

Right, sadly that won't be done anytime soon.

src/modules/navigator/mission_block.cpp Outdated Show resolved Hide resolved
src/modules/navigator/mission_feasibility_checker.cpp Outdated Show resolved Hide resolved
src/modules/navigator/mission_feasibility_checker.cpp Outdated Show resolved Hide resolved
@@ -86,6 +86,8 @@ param set MAV_SYS_ID $((px4_instance+1))
simulator_tcp_port=$((4560+px4_instance))
udp_offboard_port_local=$((14580+px4_instance))
udp_offboard_port_remote=$((14540+px4_instance))
udp_onboard_payload_port_local=$((14558+px4_instance))
Copy link
Member

Choose a reason for hiding this comment

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

This will conflict with udp_offboard_port_local after 22 instances. Would it be possible to find another slot? Regarding patterns I think the first port is defined up to the decimal, to be consistent with the others

This enables the vehicle to be able to wait with executing the next item until a position has been passed.
… mission

This enables the navigator to wait for a specific gate coordinate to pass orthogonally to the current trajectory. This is particularly helpful for payload / camera handling in missions and avoids a dependency of payload handling on navigation waypoints.
This allows to test plane survey missions with the camera trigger included in SITL.
This is to allow us to test triggering properly in SITL
Boolean logic improvement to avoid double assignment of true
A mission with zero elements is invalid but should not lead to a warning. Previously a fixed wing aircraft without a mission did emit warnings about a missing land item.
This helps to trace the code, no functional changes.
This helps to fly smaller / faster test missions.
Previously a zero-length mission that failed checks
(e.g. because a mandatory element was not present) would lead to a
warning.
This diff does not contain any functional changes but just makes the code more readable and adds comments.
The default for the gate check condition is to pass and this needed to be explicitly documented
This change simplifies the gate calculation.
The mission logic depends in a number of locations on being able to calculate the direction from one waypoint to another. Missions that have waypoints that are in the same physical location do not make sense and need to be rejected (the GCS / SDK generating them needs to be fixed). By enforcing this we can work with a reasonable and simpler state machine while executing the mission.
We have a plane_cam configuration for survey applications instead.
@LorenzMeier LorenzMeier force-pushed the pr-survey-trigger-control-rebased branch from fb94b9a to 1eafb20 Compare March 14, 2020 15:42
@LorenzMeier
Copy link
Member Author

I've accounted for all the comments - merging.

@moreba1
Copy link
Contributor

moreba1 commented Sep 4, 2020

I can not upload a mission with QGC when mav_cmd_condition_gate enabled.
@LorenzMeier

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.

6 participants