Skip to content

Commit d2212d8

Browse files
author
Andrew Lui
committed
revise tf broadcast to tf2_ros in pose queries functions, pose transform functions, object transform boardcast functions in commander_moveit.py and add functions to pose_tools as a consequence, remove the use of GeneralCommanderFactory in all the example programs (the use of GeneralCommanderFactory is not recommended because the use case is not practical, added launch files for two different robots
1 parent f94a7a0 commit d2212d8

26 files changed

Lines changed: 740 additions & 143 deletions

README.md

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,12 @@ Use the [Documentation Entry Point](http://REF-RAS.github.io/arm_commander) to b
2424
The arm commander presents a programming interface dedicated to robot arm manipulation and encapsulates useful but tedious programming components such as ROS and arm movement planning. The arm commander can support the development of applications using or not using ROS. The following example uses the arm commander API to move the end-effector of the robot arm `panda_arm` to the position (0.6, 0.0, 0.4), and then move it to another position (0.4, 0.2, 0.4)
2525

2626
```
27-
from arm_commander.commander_moveit import GeneralCommander, GeneralCommanderFactory
27+
from arm_commander.commander_moveit import GeneralCommander
2828
2929
class ArmCommanderMoveExample():
3030
def __init__(self):
3131
# create the General Commander and wait for it being ready to service move commands
32-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
32+
arm_commander: GeneralCommander = GeneralCommander('panda_arm')
3333
arm_commander.spin(spin_in_thread=True)
3434
arm_commander.wait_for_ready_to_move()
3535
# send two move commands one after another

arm_commander/commander_moveit.py

Lines changed: 91 additions & 79 deletions
Large diffs are not rendered by default.

arm_commander/tools/pose_tools.py

Lines changed: 26 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,9 @@
1010
__status__ = 'Development'
1111

1212
import math
13-
import rospy, tf
13+
import rospy
1414
import tf.transformations
15-
from geometry_msgs.msg import Pose, PoseStamped, Point, Quaternion
15+
from geometry_msgs.msg import Pose, PoseStamped, Point, Quaternion, TransformStamped, Transform, Vector3, PointStamped
1616

1717
def list_to_pose(pose) -> Pose:
1818
""" Convert a pose in xyzrpy or xyzq format to Pose
@@ -90,6 +90,30 @@ def list_to_xyzrpy(pose) -> list:
9090
else:
9191
return pose[:3] + list(tf.transformations.euler_from_quaternion(pose[3:]))
9292

93+
def transform_to_pose_stamped(transform:TransformStamped) -> PoseStamped:
94+
""" Convert a TransformStamped object into PoseStamped object
95+
96+
"""
97+
point = Point(transform.transform.translation.x, transform.transform.translation.y, transform.transform.translation.z)
98+
quaternion = Quaternion(transform.transform.rotation.x, transform.transform.rotation.y, transform.transform.rotation.z, transform.transform.rotation.w)
99+
return PoseStamped(transform.header, Pose(point, quaternion))
100+
101+
def pose_stamped_to_transform_stamped(pose_stamped:PoseStamped, reference_frame:str) -> TransformStamped:
102+
""" Convert a PoseStamped object into TransformStamped object
103+
104+
"""
105+
translation = Vector3(pose_stamped.pose.position.x, pose_stamped.pose.position.y, pose_stamped.pose.position.z)
106+
transform = Transform(translation, pose_stamped.pose.orientation)
107+
transform_stamped = TransformStamped(pose_stamped.header, reference_frame, transform)
108+
return transform_stamped
109+
110+
def pose_stamped_to_point_stamped(pose_stamped:PoseStamped) -> PointStamped:
111+
""" Convert a PoseStamped object into PointStamped object
112+
113+
"""
114+
point_stamped = PointStamped(pose_stamped.header, pose_stamped.pose.position)
115+
return point_stamped
116+
93117
def same_rpy_with_tolerence(rpy_1:list, rpy_2:list, tolerance:float=0.01) -> bool:
94118
""" test if two euler's angles are the same
95119

docs/source/API_SUMMARY.md

Lines changed: 1 addition & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -13,16 +13,6 @@ This page provides a summary of the API. Refer to the [Full API Reference](arm_c
1313

1414
The **Arm Commander** is a Python object of the class `GeneralCommander` that represents the commander of a particular __arm__ or manipulation device. An application can use more than one `GeneralCommander` object if a robot arm platform comprising multiple manipulators.
1515

16-
### Factory for Creating Arm Commander
17-
18-
The function `get_object` of the class `GeneralCommanderFactory` returns the __singleton__ `GeneralCommander` object for a particular manipulator name. The current version is coupled with Moveit 1 and the moveit group name is to be provided to the factory.
19-
20-
#### GeneralCommanderFactory
21-
22-
| Function | Parameters | Remarks |
23-
| -------- | ---------- | ------- |
24-
| get_object | The manipulator group name and optionally the name of the world reference frame | |
25-
2616
### System Parameters
2717

2818
| Functions | Parameters | Remarks |
@@ -61,15 +51,14 @@ The function `get_object` of the class `GeneralCommanderFactory` returns the __s
6151

6252
| Functions | Parameters | Remarks |
6353
| -------- | ---------- | ------- |
64-
| get_latest_moveit_feedback | | Returns the latest `MoveGroupActionFeedback` received |
6554
| get_error_code | | Returns the latest error code received |
6655

6756

6857
### Example: Essential Startup Sequence in Applications
6958

7059
The following shows the essential `GeneralCommander` startup sequence in applications.
7160
```python
72-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
61+
arm_commander:GeneralCommander = GeneralCommander('panda_arm')
7362
arm_commander.spin(spin_in_thread=True)
7463
arm_commander.wait_for_ready_to_move()
7564
```

docs/source/TUTORIAL_PART1.md

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ Example programs are provided for illustrating how to use the **general arm comm
2020
## Programming Essentials
2121

2222
The essential Python modules are found in the following three files.
23-
- `commander_moveit.py`: defines main classes including the `GeneralCommander` and the factory class `GeneralCommanderFactory`.
23+
- `commander_moveit.py`: defines main classes including the `GeneralCommander`.
2424
- `states.py`: defines the key `Enum` classes for state management.
2525
- `moveit_tools.py`: defines utility and helper functions.
2626

@@ -29,7 +29,7 @@ The essential Python modules are found in the following three files.
2929
To use the Python arm_commander interface, import the modules in the concerned Python program file as below.
3030

3131
```python
32-
from arm_commander.commander_moveit import GeneralCommander, GeneralCommanderFactory
32+
from arm_commander.commander_moveit import GeneralCommander
3333
from arm_commander.states import ControllerState, GeneralCommanderStates
3434
import arm_commander.moveit_tools as moveit_tools
3535
```
@@ -43,7 +43,7 @@ The program file `move/simple_move_1.py` illustrates the essentials of programmi
4343
The string parameter `panda_arm` specifies the __move_group__ as defined in the robot arm configuration (`panda_moveit_config`).
4444

4545
```python
46-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
46+
arm_commander:GeneralCommander = GeneralCommander('panda_arm')
4747
arm_commander.spin(spin_in_thread=True)
4848
arm_commander.wait_for_ready_to_move()
4949
```
@@ -62,7 +62,7 @@ Alternatively, the client can create a new thread and use it to execute the spin
6262
class ArmCommanderMoveExample():
6363
def __init__(self):
6464
...
65-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
65+
arm_commander:GeneralCommander = GeneralCommander('panda_arm')
6666
self.arm_commander = arm_commander
6767
self.the_thread = threading.Thread(target=self.spin_commander, daemon=True)
6868
self.the_thread.start()
@@ -81,7 +81,7 @@ class ArmCommanderMoveExample():
8181
def __init__(self):
8282
...
8383
signal.signal(signal.SIGINT, self.stop)
84-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
84+
arm_commander: GeneralCommander = GeneralCommander('panda_arm')
8585
self.arm_commander = arm_commander
8686
...
8787

examples/collision/avoid_object.py

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
__email__ = 'robotics.ref@qut.edu.au'
1414
__status__ = 'Development'
1515

16-
import sys, signal
17-
from arm_commander.commander_moveit import GeneralCommander, GeneralCommanderFactory
16+
import sys, signal, time
17+
from arm_commander.commander_moveit import GeneralCommander
1818
import arm_commander.tools.moveit_tools as moveit_tools
1919

2020
class ArmCommanderCollisionAvoidExample():
@@ -26,7 +26,7 @@ def __init__(self):
2626
# rospy.init_node('moveit_general_commander_node', anonymous=False)
2727
signal.signal(signal.SIGINT, self.stop)
2828
# create the General Commander and wait for it being ready to service move commands
29-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
29+
arm_commander:GeneralCommander = GeneralCommander('panda_arm')
3030
arm_commander.spin(spin_in_thread=True)
3131
arm_commander.reset_world() # to remove any workspace or object previously defined
3232
arm_commander.wait_for_ready_to_move()
@@ -48,7 +48,9 @@ def __init__(self):
4848
# move to the top of the object
4949
xyzrpy = [0.4, 0.0, 0.6, 3.14, 0.0, 0.6]
5050
arm_commander.move_to_pose(xyzrpy, wait=True)
51-
arm_commander.reset_state()
51+
arm_commander.reset_state()
52+
53+
time.sleep(5)
5254

5355
def stop(self, *args, **kwargs):
5456
self.arm_commander.abort_move()

examples/collision/avoid_object_fix_region.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
__email__ = 'robotics.ref@qut.edu.au'
1414
__status__ = 'Development'
1515

16-
import sys, signal
17-
from arm_commander.commander_moveit import GeneralCommander, GeneralCommanderFactory
16+
import sys, signal, time
17+
from arm_commander.commander_moveit import GeneralCommander
1818
import arm_commander.tools.moveit_tools as moveit_tools
1919
import arm_commander.tools.pose_tools as pose_tools
2020

@@ -27,7 +27,7 @@ def __init__(self):
2727
# rospy.init_node('moveit_general_commander_node', anonymous=False)
2828
signal.signal(signal.SIGINT, self.stop)
2929
# create the General Commander and wait for it being ready to service move commands
30-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
30+
arm_commander:GeneralCommander = GeneralCommander('panda_arm')
3131
arm_commander.spin(spin_in_thread=True)
3232
arm_commander.reset_world() # to remove any workspace or object previously defined
3333
arm_commander.wait_for_ready_to_move()
@@ -65,6 +65,9 @@ def __init__(self):
6565
arm_commander.reset_state()
6666

6767
arm_commander.clear_path_constraints()
68+
69+
time.sleep(5)
70+
6871

6972
def stop(self, *args, **kwargs):
7073
self.arm_commander.abort_move()

examples/collision/avoid_object_fix_rotation.py

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
__email__ = 'robotics.ref@qut.edu.au'
1414
__status__ = 'Development'
1515

16-
import sys, signal
17-
from arm_commander.commander_moveit import GeneralCommander, GeneralCommanderFactory
16+
import sys, signal, time
17+
from arm_commander.commander_moveit import GeneralCommander
1818
import arm_commander.tools.moveit_tools as moveit_tools
1919

2020
class ArmCommanderCollisionAvoidExample():
@@ -27,7 +27,7 @@ def __init__(self):
2727
# rospy.init_node('moveit_general_commander_node', anonymous=False)
2828
signal.signal(signal.SIGINT, self.stop)
2929
# create the General Commander and wait for it being ready to service move commands
30-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
30+
arm_commander:GeneralCommander = GeneralCommander('panda_arm')
3131
arm_commander.spin(spin_in_thread=True)
3232
arm_commander.reset_world() # to remove any workspace or object previously defined
3333
arm_commander.wait_for_ready_to_move()
@@ -61,6 +61,8 @@ def __init__(self):
6161

6262
arm_commander.clear_path_constraints()
6363

64+
time.sleep(5)
65+
6466
def stop(self, *args, **kwargs):
6567
self.arm_commander.abort_move()
6668
self.arm_commander.clear_path_constraints()

examples/collision/workspace.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
__status__ = 'Development'
1515

1616
import sys, signal
17-
from arm_commander.commander_moveit import GeneralCommander, GeneralCommanderFactory
17+
from arm_commander.commander_moveit import GeneralCommander
1818

1919
class ArmCommanderWorkspaceExample():
2020
""" This example demonstrates the following:
@@ -25,7 +25,7 @@ def __init__(self):
2525
# rospy.init_node('moveit_general_commander_node', anonymous=False)
2626
signal.signal(signal.SIGINT, self.stop)
2727
# create the General Commander and wait for it being ready to service move commands
28-
arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('panda_arm')
28+
arm_commander:GeneralCommander = GeneralCommander('panda_arm')
2929
arm_commander.spin(spin_in_thread=True)
3030
arm_commander.reset_world() # to remove any workspace or object previously defined
3131
arm_commander.wait_for_ready_to_move()

examples/commander_demo.py

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
from arm_commander.states import ControllerState, GeneralCommanderStates
2020
import arm_commander.tools.moveit_tools as moveit_tools
2121
import arm_commander.tools.pose_tools as pose_tools
22-
from arm_commander.commander_moveit import GeneralCommander, GeneralCommanderFactory, logger
22+
from arm_commander.commander_moveit import GeneralCommander, logger
2323

2424
class GeneralCommanderDemo():
2525
""" A demo program for the :class:'GeneralCommander', which illustrates the movement commands offered by
@@ -41,8 +41,8 @@ def __init__(self, config_file='panda_demo.yaml'):
4141
logger.error(f'Error in loading demo config file {config_file}')
4242
raise
4343
# TODO: config input to factory for group name and base
44-
self.arm_commander: GeneralCommander = GeneralCommanderFactory.get_object(self.demo_config['moveit_group_name'])
45-
# self.arm_commander: GeneralCommander = GeneralCommanderFactory.get_object('xarm7', 'link_base')
44+
self.arm_commander:GeneralCommander = GeneralCommander(self.demo_config['moveit_group_name'])
45+
# self.arm_commander:GeneralCommander = GeneralCommander('xarm7', 'link_base')
4646
# self.arm_servo: CommanderServo = CommanderServo(moveit_group_name='xarm7', world_link='link_base')
4747
self.arm_commander.spin(spin_in_thread=True)
4848

@@ -295,7 +295,6 @@ def test_2(self):
295295
break
296296
time.sleep(0.1)
297297
logger.info(f'the commander has completed with the result: {the_state} {the_state.message}')
298-
# logger.info(f'Final result: {arm_commander.get_latest_moveit_feedback()}')
299298
arm_commander.reset_state()
300299
logger.info(f'=== Test 2: Finished')
301300

0 commit comments

Comments
 (0)