Skip to content

Commit

Permalink
CI: add iris optical flow to jenkins ros tests
Browse files Browse the repository at this point in the history
  • Loading branch information
lamping7 committed Oct 18, 2019
1 parent 95dc522 commit 75d15a0
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 6 deletions.
6 changes: 6 additions & 0 deletions .ci/Jenkinsfile-SITL_tests
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,12 @@ pipeline {
mission: "",
vehicle: "iris"
],
[
name: "MC_optical_flow",
test: "mavros_posix_tests_iris_opt_flow.test",
mission: "",
vehicle: ""
],

[
name: "Rover 1",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ def test_attctl(self):
boundary_z = 20

# make sure the simulation is ready to start the mission
self.wait_for_topics(60)
self.wait_for_topics(60, ignore_gps=True)
self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND,
10, -1)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,9 +155,11 @@ def reach_position(self, x, y, z, timeout):
#
def test_posctl(self):
"""Test offboard position control"""
positions = ((0, 0, 0), (50, 50, 20), (50, -50, 20), (-50, -50, 20),
(0, 0, 20))

# make sure the simulation is ready to start the mission
self.wait_for_topics(60)
self.wait_for_topics(60, ignore_gps=True)
self.wait_for_landed_state(mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND,
10, -1)

Expand All @@ -166,9 +168,6 @@ def test_posctl(self):
self.set_arm(True, 5)

rospy.loginfo("run mission")
positions = ((0, 0, 0), (50, 50, 20), (50, -50, 20), (-50, -50, 20),
(0, 0, 20))

for i in xrange(len(positions)):
self.reach_position(positions[i][0], positions[i][1],
positions[i][2], 30)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -223,11 +223,16 @@ def set_mode(self, mode, timeout):
"failed to set mode | new mode: {0}, old mode: {1} | timeout(seconds): {2}".
format(mode, old_mode, timeout)))

def wait_for_topics(self, timeout):
def wait_for_topics(self, timeout, ignore_gps=False):
"""wait for simulation to be ready, make sure we're getting topic info
from all topics by checking dictionary of flag values set in callbacks,
timeout(int): seconds"""
rospy.loginfo("waiting for subscribed topics to be ready")

if ignore_gps:
self.sub_topics_ready.pop('global_pos', None)
self.sub_topics_ready.pop('home_pos', None)

loop_freq = 1 # Hz
rate = rospy.Rate(loop_freq)
simulation_ready = False
Expand Down
10 changes: 10 additions & 0 deletions platforms/posix/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -165,9 +165,19 @@ elseif ("${PX4_BOARD}" MATCHES "sitl")
${PROJECT_NAME}/build/px4_sitl_default
FILES_MATCHING
PATTERN "CMakeFiles" EXCLUDE
PATTERN "OpticalFlow" EXCLUDE
PATTERN "*.so"
)

# sitl_gazebo built optical flow plugin
install(
FILES
${PROJECT_SOURCE_DIR}/build/px4_sitl_default/build_gazebo/OpticalFlow/libOpticalFlow.so
DESTINATION
${PROJECT_NAME}/build/px4_sitl_default/build_gazebo
OPTIONAL
)

# sitl_gazebo dirs
install(
DIRECTORY
Expand Down

0 comments on commit 75d15a0

Please sign in to comment.