Skip to content

Commit

Permalink
[RosTest] refactor the flight control test script to be based on the …
Browse files Browse the repository at this point in the history
…new state machine system
  • Loading branch information
Moju Zhao authored and tongtybj committed Jan 12, 2025
1 parent 22eca8d commit d2846e7
Show file tree
Hide file tree
Showing 10 changed files with 540 additions and 271 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/catkin_lint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -31,4 +31,4 @@ jobs:
wstool init
wstool merge aerial_robot_noetic.rosinstall
wstool update
ROS_DISTRO=noetic catkin_lint --resolve-env --strict $PWD --skip-path kalman_filter --skip-path ublox_gps --skip-path aerial_robot_3rdparty --skip-path rosserial --skip-path livox_ros_driver2 --skip-path fast_lio --skip-path mocap_optitrack --skip-path aerial_robot_base
ROS_DISTRO=noetic catkin_lint --resolve-env --strict $PWD --skip-path kalman_filter --skip-path ublox_gps --skip-path aerial_robot_3rdparty --skip-path rosserial --skip-path livox_ros_driver2 --skip-path fast_lio --skip-path mocap_optitrack
122 changes: 0 additions & 122 deletions aerial_robot_base/src/aerial_robot_base/hovering_check.py

This file was deleted.

112 changes: 112 additions & 0 deletions aerial_robot_base/test/hovering_check.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
#!/usr/bin/env python
# -*- coding: utf-8 -*-

# Software License Agreement (BSD License)

# Copyright (c) 2025, DRAGON Laboratory, The University of Tokyo
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
# * Neither the name of the Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

import sys
import unittest

import rospy
import rostest
from aerial_robot_base.state_machine import *
from std_msgs.msg import Empty


PKG = 'rostest'

# Template for simple demo
class HoverMotion():
def __init__(self):
self.robot = RobotInterface()

self.sm_top = smach.StateMachine(outcomes=['succeeded', 'preempted'])
self.sm_top.userdata.flags = {}
self.sm_top.userdata.extra = {}

with self.sm_top:
smach.StateMachine.add('Start', Start(self.robot),
transitions={'succeeded':'Arm',
'preempted':'preempted'},
remapping={'flags':'flags', 'extra':'extra'})


smach.StateMachine.add('Arm', Arm(self.robot),
transitions={'succeeded':'Takeoff',
'preempted':'preempted'},
remapping={'flags':'flags', 'extra':'extra'})

smach.StateMachine.add('Takeoff', Takeoff(self.robot),
transitions={'succeeded':'WayPoint',
'preempted':'preempted'},
remapping={'flags':'flags', 'extra':'extra'})


smach.StateMachine.add('WayPoint', WayPoint(self.robot),
transitions={'succeeded':'Land',
'preempted':'preempted'},
remapping={'flags':'flags', 'extra':'extra'})

smach.StateMachine.add('Land', Land(self.robot),
transitions={'succeeded':'succeeded',
'preempted':'preempted'},
remapping={'flags':'flags', 'extra':'extra'})

self.sis = smach_ros.IntrospectionServer('task_smach_server', self.sm_top, '/SM_ROOT')


def startMotion(self):
self.sis.start()
outcome = self.sm_top.execute()

self.sis.stop()

if outcome == 'succeeded':
return True
else:
return False


class HoveringTest(unittest.TestCase):
def __init__(self, *args):
super(self.__class__, self).__init__(*args)
rospy.init_node("hovering_test")

def test_hovering(self):
checker = HoverMotion()
self.assertTrue(checker.startMotion())

if __name__ == '__main__':
print("start check hovering")
try:
rostest.run(PKG, 'hovering_check', HoveringTest, sys.argv)
except KeyboardInterrupt:
pass

print("exiting")
109 changes: 44 additions & 65 deletions robots/dragon/test/dragon_control.test
Original file line number Diff line number Diff line change
Expand Up @@ -3,88 +3,67 @@
<arg name="robot_id" default=""/>
<arg name="robot_ns" value="dragon$(arg robot_id)"/>
<arg name="full_vectoring_mode" default= "false" />
<arg name="mujoco" default= "false" />

<include file="$(find dragon)/launch/bringup.launch">
<arg name="real_machine" value="False" />
<arg name="simulation" value="True" />
<arg name="robot_id" value="$(arg robot_id)"/>
<arg name="full_vectoring_mode" value= "$(arg full_vectoring_mode)" />
<arg name="headless" value="$(arg headless)" />
<arg name="mujoco" value="$(arg mujoco)" />
<arg name="demo" value="False" />
</include>

<!-- test codes -->
<!-- 1. topics -->
<test name="publishtest" test-name="publishtest" pkg="rostest" type="publishtest" ns="$(arg robot_ns)" retry="1">
<test test-name="control_test" pkg="dragon" type="flight_check.py" name="flight_test" ns="$(arg robot_ns)" time-limit="180" retry="3" unless ="$(arg full_vectoring_mode)" >
<rosparam>
topics:
- name: uav/cog/odom
timeout: 5.0
init_form:
joint_names: ['joint1_pitch', 'joint1_yaw', 'joint2_pitch', 'joint2_yaw', 'joint3_pitch', 'joint3_yaw']
joint_angles: [0, 1.57, 0, 1.57, 0, 1.57]
angle_thresh: 0.08
timeout: 20.0
takeoff:
timeout: 30.0
hold_time: 2.0
motion:
joint_names: ['joint1_pitch', 'joint1_yaw', 'joint2_pitch', 'joint2_yaw', 'joint3_pitch', 'joint3_yaw']
joint_trajectory: [[-0.6, -1.57, -0.6, 0, 0, 1.57], [0, 1.57, 0, 1.57, 0, 1.57], [-0.8, 1.2, -0.8, 1.2, -0.8, 1.2], [0, 1.57, 0, 1.57, 0, 1.57], [0.0, 1.57, -1.5, 0.0, 0.0, 1.57]]
rot_trajectory: [[0.0, -0.3], [0, 0], [-0.4, 0.4], [0, 0], [0, 0.75]]
joint_thresh: 0.04
pos_thresh: [0.05, 0.05, 0.05]
rot_thresh: [0.05, 0.05, 0.05]
timeout: 20.0
hold_time: 2.0
stable_check:
pose_thresh: [0.1, 0.15, 0.1]
</rosparam>
</test>

<!-- 2. control -->
<test test-name="control_test" pkg="hydrus" type="control_check.py" name="control_test" ns="$(arg robot_ns)" time-limit="180" retry="3" unless ="$(arg full_vectoring_mode)" >
<test test-name="control_test" pkg="dragon" type="flight_check.py" name="flight_test" ns="$(arg robot_ns)" time-limit="180" retry="3" if ="$(arg full_vectoring_mode)" >
<rosparam>
hovering_duration: 30.0
convergence_thresholds: [0.02, 0.02, 0.02] # hovering threshold
init_joint_names: ['joint1_pitch', 'joint1_yaw', 'joint2_pitch', 'joint2_yaw', 'joint3_pitch', 'joint3_yaw']
init_joint_angles: [0, 1.57, 0, 1.57, 0, 1.57]
tasks:
- command: "rosrun dragon transformation_demo.py _mode:=0 _reset:=0"
threshold: [0.1, 0.08, 0.08]
angle_threshold: 0.02
timeout: 20
reset: "rosrun dragon transformation_demo.py _mode:=0 _reset:=1"
reset_duration: 20
- command: "rosrun dragon transformation_demo.py _mode:=1 _reset:=0"
threshold: [0.08, 0.08, 0.05]
angle_threshold: 0.02
timeout: 10
reset: "rosrun dragon transformation_demo.py _mode:=0 _reset:=1"
reset_duration: 10
- command: "rosrun dragon transformation_demo.py _mode:=2 _reset:=0"
threshold: [0.15, 0.08, 0.12]
angle_threshold: 0.02
timeout: 15
reset: "rosrun dragon transformation_demo.py _mode:=0 _reset:=1"
reset_duration: 10
init_form:
joint_names: ['joint1_pitch', 'joint1_yaw', 'joint2_pitch', 'joint2_yaw', 'joint3_pitch', 'joint3_yaw']
joint_angles: [0, 1.57, 0, 1.57, 0, 1.57]
angle_thresh: 0.08
timeout: 20.0
takeoff:
timeout: 30.0
hold_time: 2.0
motion:
joint_names: ['joint1_pitch', 'joint1_yaw', 'joint2_pitch', 'joint2_yaw', 'joint3_pitch', 'joint3_yaw']
joint_trajectory: [[0, 1.57, 0, 1.57, 0, 1.57], [0, 1.57, 0, 1.57, 0, -1.57], [0, 1.57, 0, 0, 0, -1.57]]
rot_trajectory: [[-1.5708, 0], [-1.5708, 0], [-1.5708, 0]]
joint_thresh: 0.04
pos_thresh: [0.05, 0.05, 0.05]
rot_thresh: [0.05, 0.05, 0.05]
timeout: 20.0
hold_time: 2.0
stable_check:
pose_thresh: [0.1, 0.1, 0.1]
</rosparam>
<param name="init_form_duration" value="30.0" />
<param name="init_angle_threshold" value="0.04" />
</test>

<test test-name="control_test" pkg="hydrus" type="control_check.py" name="control_test" ns="$(arg robot_ns)" time-limit="180" retry="3" if ="$(arg full_vectoring_mode)" >
<rosparam>
hovering_duration: 30.0
convergence_thresholds: [0.02, 0.02, 0.02] # hovering threshold
init_joint_names: ['joint1_pitch', 'joint1_yaw', 'joint2_pitch', 'joint2_yaw', 'joint3_pitch', 'joint3_yaw']
init_joint_angles: [0, 1.57, 0, 1.57, 0, 1.57]
tasks:
- command: "rostopic pub -1 /dragon/final_target_baselink_rot spinal/DesireCoord -- -1.5708 0.0 0.0 0"
threshold: [0.06, 0.06, 0.06]
angle_threshold: 0.02
timeout: 15
reset_duration: 0
- command: "rosrun dragon transformation_demo_vertical.py _mode:=0"
threshold: [0.08, 0.08, 0.06]
angle_threshold: 0.02
timeout: 20
reset_duration: 0
- command: "rosrun dragon transformation_demo_vertical.py _mode:=1"
threshold: [0.08, 0.08, 0.06]
angle_threshold: 0.02
timeout: 20
reset_duration: 0
<!-- TDOO: mode2 of transformation_demo_vertical.py is unstable in gazebo
- command: "rosrun dragon transformation_demo_vertical.py _mode:=1"
threshold: [0.05, 0.05, 0.05]
angle_threshold: 0.02
timeout: 20
reset_duration: 0
-->
</rosparam>
<param name="init_form_duration" value="30.0" />
<param name="init_angle_threshold" value="0.04" />
</test>
<node name="task_task_trigger" pkg="rostopic" type="rostopic" args="pub -1 /task_start std_msgs/Empty" launch-prefix="bash -c 'sleep 5.0; $0 $@' "/>

</launch>
Loading

0 comments on commit d2846e7

Please sign in to comment.