Skip to content

Commit

Permalink
- publish offboard mode with manual input so the vehicle control stat…
Browse files Browse the repository at this point in the history
…us is correct

- trigger offboard in mavros attitude test
  • Loading branch information
AndreasAntener committed Mar 2, 2015
1 parent 9574c6d commit 5a402ed
Show file tree
Hide file tree
Showing 3 changed files with 34 additions and 4 deletions.
33 changes: 31 additions & 2 deletions integrationtests/demo_tests/manual_input.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,20 +39,23 @@
import rospy

from px4.msg import manual_control_setpoint
from px4.msg import offboard_control_mode
from mav_msgs.msg import CommandAttitudeThrust
from std_msgs.msg import Header

#
# Manual input control helper
#
# FIXME: this is not the way to do it! ATM it fakes input to iris/command/attitude because else
# the simulator does not instantiate our controller.
# the simulator does not instantiate our controller. Probably this whole class will disappear once
# arming works correctly.
#
class ManualInput:

def __init__(self):
rospy.init_node('test_node', anonymous=True)
self.pubMcsp = rospy.Publisher('px4_multicopter/manual_control_setpoint', manual_control_setpoint, queue_size=10)
self.pubOff = rospy.Publisher('px4_multicopter/offboard_control_mode', offboard_control_mode, queue_size=10)
self.pubAtt = rospy.Publisher('iris/command/attitude', CommandAttitudeThrust, queue_size=10)

def arm(self):
Expand Down Expand Up @@ -119,9 +122,35 @@ def posctl(self):
rate.sleep()
count = count + 1

def offboard(self):

def offboard_attctl(self):
self.offboard(False, False, True, True, True, True)

def offboard_posctl(self):
self.offboard(False, False, True, False, True, True)

# Trigger offboard and set offboard control mode before
def offboard(self, ignore_thrust=False, ignore_attitude=False, ignore_bodyrate=True,
ignore_position=False, ignore_velocity=True, ignore_acceleration_force=True):
rate = rospy.Rate(10) # 10hz

mode = offboard_control_mode()
mode.ignore_thrust = ignore_thrust
mode.ignore_attitude = ignore_attitude
mode.ignore_bodyrate = ignore_bodyrate
mode.ignore_position = ignore_position
mode.ignore_velocity = ignore_velocity
mode.ignore_acceleration_force = ignore_acceleration_force

count = 0
while not rospy.is_shutdown() and count < 5:
rospy.loginfo("setting offboard mode")
time = rospy.get_rostime().now()
mode.timestamp = time.secs * 1e6 + time.nsecs / 1000
self.pubOff.publish(mode)
rate.sleep()
count = count + 1

# triggers offboard
pos = manual_control_setpoint()
pos.x = 0
Expand Down
3 changes: 2 additions & 1 deletion integrationtests/demo_tests/mavros_offboard_attctl_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,7 @@ def test_attctl(self):
# FIXME: this must go ASAP when arming is implemented
manIn = ManualInput()
manIn.arm()
manIn.offboard_attctl()

self.assertTrue(self.arm(), "Could not arm")
self.rateSec.sleep()
Expand All @@ -111,7 +112,7 @@ def test_attctl(self):
att.header = Header()
att.header.frame_id = "base_footprint"
att.header.stamp = rospy.Time.now()
quaternion = quaternion_from_euler(0.2, 0.2, 0)
quaternion = quaternion_from_euler(0.15, 0.15, 0)
att.pose.orientation = Quaternion(*quaternion)

throttle = Float64()
Expand Down
2 changes: 1 addition & 1 deletion integrationtests/demo_tests/mavros_offboard_posctl_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ def test_posctl(self):
# FIXME: this must go ASAP when arming is implemented
manIn = ManualInput()
manIn.arm()
manIn.offboard()
manIn.offboard_posctl()

self.assertTrue(self.arm(), "Could not arm")
self.rateSec.sleep()
Expand Down

0 comments on commit 5a402ed

Please sign in to comment.