mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
auto-format python code with black
This commit is contained in:
parent
10adb63f4a
commit
fd25a0626a
@ -42,14 +42,12 @@ class Test(unittest.TestCase):
|
||||
|
||||
def test_Merger(self):
|
||||
cartesian = core.CartesianPath()
|
||||
|
||||
def createDisplacement(group, displacement):
|
||||
move = stages.MoveRelative("displace", cartesian)
|
||||
move.group = group
|
||||
move.ik_frame = PoseStamped(header=Header(frame_id="tool0"))
|
||||
dir = Vector3Stamped(
|
||||
header = Header(frame_id = "base_link"),
|
||||
vector = Vector3(*displacement)
|
||||
)
|
||||
dir = Vector3Stamped(header=Header(frame_id="base_link"), vector=Vector3(*displacement))
|
||||
move.setDirection(dir)
|
||||
move.restrictDirection(stages.MoveRelative.Direction.FORWARD)
|
||||
return move
|
||||
@ -67,6 +65,6 @@ class Test(unittest.TestCase):
|
||||
task.publish(task.solutions[0])
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
if __name__ == "__main__":
|
||||
roscpp_init("test_mtc")
|
||||
rostest.rosrun("", "", Test)
|
||||
|
||||
@ -143,9 +143,11 @@ class TestStages(unittest.TestCase):
|
||||
except TypeError as e:
|
||||
pass
|
||||
except:
|
||||
self.fail("Assigning {} did raise wrong exception: {}".format(value, sys.exc_info()[0]))
|
||||
msg = "Assigning {} did raise wrong exception: {}"
|
||||
self.fail(msg.format(value, sys.exc_info()[0]))
|
||||
else:
|
||||
self.fail("Assigning {} did not raise an exception, result: {}".format(value, getattr(stage, name)))
|
||||
msg = "Assigning {} did not raise an exception, result: {}"
|
||||
self.fail(msg.format(value, getattr(stage, name)))
|
||||
|
||||
def test_CurrentState(self):
|
||||
stage = stages.CurrentState("current")
|
||||
@ -194,7 +196,7 @@ class TestStages(unittest.TestCase):
|
||||
self._check(stage, "path_constraints", Constraints())
|
||||
stage.setDirection(TwistStamped())
|
||||
stage.setDirection(Vector3Stamped())
|
||||
stage.setDirection({'joint': 0.1})
|
||||
stage.setDirection({"joint": 0.1})
|
||||
|
||||
def test_Connect(self):
|
||||
planner = core.PipelinePlanner()
|
||||
@ -290,5 +292,5 @@ class TestTask(unittest.TestCase):
|
||||
task.add(stages.FixedState())
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
||||
|
||||
@ -5,8 +5,8 @@ from catkin_pkg.python_setup import generate_distutils_setup
|
||||
|
||||
d = generate_distutils_setup(
|
||||
# list of packages to setup
|
||||
packages = ['moveit', 'moveit.python_tools', 'moveit.task_constructor'],
|
||||
# specify location of root ('') package dir
|
||||
package_dir = {'' : 'python/src'}
|
||||
packages=["moveit", "moveit.python_tools", "moveit.task_constructor"],
|
||||
# specify location of root ("") package dir
|
||||
package_dir={"": "python/src"},
|
||||
)
|
||||
setup(**d)
|
||||
|
||||
@ -8,6 +8,7 @@ from math import pi
|
||||
import time
|
||||
|
||||
from moveit.python_tools import roscpp_init
|
||||
|
||||
roscpp_init("mtc_tutorial")
|
||||
|
||||
group = "panda_arm"
|
||||
@ -38,7 +39,7 @@ task.add(move)
|
||||
# rotate about z
|
||||
move = stages.MoveRelative("rz +45°", cartesian)
|
||||
move.group = group
|
||||
move.setDirection(TwistStamped(header=header, twist=Twist(angular=Vector3(0,0,pi/4.))))
|
||||
move.setDirection(TwistStamped(header=header, twist=Twist(angular=Vector3(0, 0, pi / 4.0))))
|
||||
task.add(move)
|
||||
|
||||
# Cartesian motion, defined as joint-space offset
|
||||
|
||||
Loading…
Reference in New Issue
Block a user