Skip to content

Commit baab43c

Browse files
ana-GTjasmeet0915
authored andcommitted
Fix canadarm's harcoded paths / update control interface / use xacro file (#23)
* Fix paths * Fix controller type * Set parameters for xyz/rpy for arm in launch file * Added joint traj controller and node for demo
1 parent 436e574 commit baab43c

File tree

7 files changed

+136
-13
lines changed

7 files changed

+136
-13
lines changed

canadarm/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@ install(DIRECTORY
4343

4444
install(PROGRAMS
4545
nodes/move_joint_server
46+
nodes/move_arm
4647
DESTINATION lib/${PROJECT_NAME}
4748
)
4849

canadarm/README.md

Lines changed: 20 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,26 @@
33

44
(This is a temp instruction before the reorg)
55

6-
Build and source the ```canadarm``` package
6+
Build and source the ```canadarm``` package:
77

88
```
99
ros2 launch canadarm canadarm.launch.py
10-
```
10+
```
11+
12+
To move the arm to an outstretched pose:
13+
14+
```
15+
ros2 service call /open_arm std_srvs/srv/Empty
16+
```
17+
18+
To move the arm to its default (close) pose of all zeros:
19+
20+
```
21+
ros2 service call /close_arm std_srvs/srv/Empty
22+
```
23+
24+
To move the arm to a random pose:
25+
26+
```
27+
ros2 service call /random_arm std_srvs/srv/Empty
28+
```

canadarm/config/canadarm_control.yaml

Lines changed: 21 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,30 @@ controller_manager:
55
canadarm_joint_controller:
66
type: effort_controllers/JointGroupPositionController
77

8+
canadarm_joint_trajectory_controller:
9+
type: joint_trajectory_controller/JointTrajectoryController
10+
811
joint_state_broadcaster:
912
type: joint_state_broadcaster/JointStateBroadcaster
1013

1114

15+
canadarm_joint_trajectory_controller:
16+
ros__parameters:
17+
joints:
18+
- Base_Joint
19+
- Shoulder_Roll
20+
- Shoulder_Yaw
21+
- Elbow_Pitch
22+
- Wrist_Pitch
23+
- Wrist_Yaw
24+
- Wrist_Roll
25+
interface_name: position
26+
command_interfaces:
27+
- position
28+
state_interfaces:
29+
- position
30+
- velocity
31+
1232
canadarm_joint_controller:
1333
ros__parameters:
1434
joints:
@@ -53,4 +73,4 @@ canadarm_joint_controller:
5373
Wrist_Roll:
5474
p: 50.0
5575
i: 10.0
56-
d: 200.0
76+
d: 200.0

canadarm/launch/canadarm.launch.py

Lines changed: 16 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -23,23 +23,30 @@ def generate_launch_description():
2323
':'.join([environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''),
2424
environ.get('LD_LIBRARY_PATH', default='')]),
2525
'IGN_GAZEBO_RESOURCE_PATH':
26-
':'.join([canadarm_demos_path])}
26+
':'.join([environ.get('IGN_GAZEBO_RESOURCE_PATH', default=''), canadarm_demos_path])}
2727

2828

29-
urdf_model_path = os.path.join(simulation_models_path, 'models', 'canadarm', 'urdf', 'SSRMS_Canadarm2.urdf')
29+
urdf_model_path = os.path.join(simulation_models_path, 'models', 'canadarm', 'urdf', 'SSRMS_Canadarm2.urdf.xacro')
3030
leo_model = os.path.join(canadarm_demos_path, 'worlds', 'simple.world')
3131

3232

33-
doc = xacro.process_file(urdf_model_path)
33+
doc = xacro.process_file(urdf_model_path, mappings={'xyz' : '1.0 0.0 1.5', 'rpy': '3.1416 0.0 0.0'})
3434
robot_description = {'robot_description': doc.toxml()}
3535

3636

37-
run_node = Node(
37+
#run_node = Node(
38+
# package="canadarm",
39+
# executable="move_joint_server",
40+
# output='screen'
41+
#)
42+
43+
run_move_arm = Node(
3844
package="canadarm",
39-
executable="move_joint_server",
45+
executable="move_arm",
4046
output='screen'
4147
)
4248

49+
4350
start_world = ExecuteProcess(
4451
cmd=['ign gazebo', leo_model, '-r'],
4552
output='screen',
@@ -74,7 +81,7 @@ def generate_launch_description():
7481

7582
load_canadarm_joint_controller = ExecuteProcess(
7683
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
77-
'canadarm_joint_controller'],
84+
'canadarm_joint_trajectory_controller'],
7885
output='screen'
7986
)
8087

@@ -84,7 +91,8 @@ def generate_launch_description():
8491
start_world,
8592
robot_state_publisher,
8693
spawn,
87-
run_node,
94+
#run_node,
95+
run_move_arm,
8896

8997
RegisterEventHandler(
9098
OnProcessExit(
@@ -98,4 +106,4 @@ def generate_launch_description():
98106
on_exit=[load_canadarm_joint_controller],
99107
)
100108
),
101-
])
109+
])

canadarm/nodes/move_arm

Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
#!/usr/bin/env python3
2+
3+
import rclpy
4+
from rclpy.node import Node
5+
from builtin_interfaces.msg import Duration
6+
7+
from std_msgs.msg import String, Float64
8+
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
9+
from std_srvs.srv import Empty
10+
11+
class MoveArm(Node):
12+
13+
def __init__(self):
14+
super().__init__('arm_node')
15+
self.arm_publisher_ = self.create_publisher(JointTrajectory, '/canadarm_joint_trajectory_controller/joint_trajectory', 10)
16+
self.open_srv = self.create_service(Empty, 'open_arm', self.open_arm_callback)
17+
self.close_srv = self.create_service(Empty, 'close_arm', self.close_arm_callback)
18+
self.random_srv = self.create_service(Empty, 'random_arm', self.random_arm_callback)
19+
20+
21+
def open_arm_callback(self, request, response):
22+
traj = JointTrajectory()
23+
traj.joint_names = ["Base_Joint", "Shoulder_Roll", "Shoulder_Yaw", "Elbow_Pitch", "Wrist_Pitch", "Wrist_Yaw", "Wrist_Roll"]
24+
25+
point1 = JointTrajectoryPoint()
26+
point1.positions = [0.0, 0.0, 0.0, -3.1416, 0.0, 0.0, 0.0]
27+
point1.time_from_start = Duration(sec=4)
28+
29+
traj.points.append(point1)
30+
self.arm_publisher_.publish(traj)
31+
32+
33+
return response
34+
35+
def close_arm_callback(self, request, response):
36+
traj = JointTrajectory()
37+
traj.joint_names = ["Base_Joint", "Shoulder_Roll", "Shoulder_Yaw", "Elbow_Pitch", "Wrist_Pitch", "Wrist_Yaw", "Wrist_Roll"]
38+
39+
point1 = JointTrajectoryPoint()
40+
point1.positions = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
41+
point1.time_from_start = Duration(sec=4)
42+
43+
traj.points.append(point1)
44+
self.arm_publisher_.publish(traj)
45+
46+
return response
47+
48+
def random_arm_callback(self, request, response):
49+
traj = JointTrajectory()
50+
traj.joint_names = ["Base_Joint", "Shoulder_Roll", "Shoulder_Yaw", "Elbow_Pitch", "Wrist_Pitch", "Wrist_Yaw", "Wrist_Roll"]
51+
52+
point1 = JointTrajectoryPoint()
53+
point1.positions = [1.0, -1.5, 2.0, -3.2, 0.8, 0.5, -1.0]
54+
point1.time_from_start = Duration(sec=4)
55+
56+
traj.points.append(point1)
57+
self.arm_publisher_.publish(traj)
58+
59+
return response
60+
61+
62+
def main(args=None):
63+
rclpy.init(args=args)
64+
65+
arm_node = MoveArm()
66+
67+
rclpy.spin(arm_node)
68+
# Destroy the node explicitly
69+
# (optional - otherwise it will be done automatically
70+
# when the garbage collector destroys the node object)
71+
arm_node.destroy_node()
72+
rclpy.shutdown()
73+
74+
75+
if __name__ == '__main__':
76+
main()

canadarm/nodes/move_joint_server

100644100755
File mode changed.

canadarm/worlds/simple.world

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@
4747
<visual name='visual'>
4848
<geometry>
4949
<mesh>
50-
<uri>/home/spaceros-user/demos_ws/install/simulation/share/simulation/models/canadarm/meshes/earth.dae</uri>
50+
<uri>model://canadarm/meshes/earth.dae</uri>
5151
<scale>3 3 3</scale>
5252
</mesh>
5353
</geometry>
@@ -77,7 +77,7 @@
7777
<visual name='visual'>
7878
<geometry>
7979
<mesh>
80-
<uri>/home/spaceros-user/demos_ws/install/simulation/share/simulation/models/canadarm/meshes/iss.dae</uri>
80+
<uri>model://canadarm/meshes/iss.dae</uri>
8181
<scale>1 1 1</scale>
8282
</mesh>
8383
</geometry>

0 commit comments

Comments
 (0)