Planning actually works
renamed joints in controller added semantic robot definition to rviz set default robot state back to static (no more spinny) added collision detection
This commit is contained in:
parent
754d5d5d4c
commit
9cc4ad82f5
4 changed files with 29 additions and 9 deletions
|
@ -6,10 +6,9 @@ joint_trajectory_controller:
|
||||||
type: FollowJointTrajectory
|
type: FollowJointTrajectory
|
||||||
default: true
|
default: true
|
||||||
joints:
|
joints:
|
||||||
- joint1
|
- joint_1
|
||||||
- joint2
|
- joint_2
|
||||||
- joint3
|
- joint_3
|
||||||
- joint4
|
- joint_4
|
||||||
- joint5
|
- joint_5
|
||||||
- joint6
|
- joint_6
|
||||||
- joint7
|
|
||||||
|
|
|
@ -61,7 +61,7 @@ def generate_launch_description():
|
||||||
executable='rviz2',
|
executable='rviz2',
|
||||||
output='log',
|
output='log',
|
||||||
arguments=['-d', join(launch_root, 'rviz', 'ar3.rviz')],
|
arguments=['-d', join(launch_root, 'rviz', 'ar3.rviz')],
|
||||||
parameters=[robot_description]),
|
parameters=[robot_description, robot_description_semantic]),
|
||||||
|
|
||||||
# Attatch robot to map
|
# Attatch robot to map
|
||||||
Node(
|
Node(
|
||||||
|
|
|
@ -47,7 +47,7 @@ class StatePublisher(Node):
|
||||||
# joint_state.position = [random.random() * pi / 2] * 6
|
# joint_state.position = [random.random() * pi / 2] * 6
|
||||||
# joint_state.position = [angle * 16, pi/2., -25 / 180 * pi, 0., 0., 0.]
|
# joint_state.position = [angle * 16, pi/2., -25 / 180 * pi, 0., 0., 0.]
|
||||||
# joint_state.position = [angle * 0.01 * random.random()] * 6
|
# joint_state.position = [angle * 0.01 * random.random()] * 6
|
||||||
joint_state.position = [0., 0., 0., 0., angle, 0.]
|
joint_state.position = [0., 0., 0., 0., 0., 0.]
|
||||||
|
|
||||||
# update transform
|
# update transform
|
||||||
# (moving in a circle with radius=2)
|
# (moving in a circle with radius=2)
|
||||||
|
|
|
@ -5,4 +5,25 @@
|
||||||
|
|
||||||
<virtual_joint child_link="base_link" name="virtual_joint" parent_frame="world" type="floating" />
|
<virtual_joint child_link="base_link" name="virtual_joint" parent_frame="world" type="floating" />
|
||||||
|
|
||||||
|
<disable_collisions link1="base_link" link2="link_1" reason="Adjacent"/>
|
||||||
|
<disable_collisions link1="base_link" link2="link_2" reason="Never"/>
|
||||||
|
<disable_collisions link1="base_link" link2="link_3" reason="Never"/>
|
||||||
|
<disable_collisions link1="base_link" link2="link_4" reason="Never"/>
|
||||||
|
<disable_collisions link1="base_link" link2="link_5" reason="Never"/>
|
||||||
|
<disable_collisions link1="base_link" link2="link_6" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent"/>
|
||||||
|
<disable_collisions link1="link_1" link2="link_3" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_1" link2="link_4" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_1" link2="link_5" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_1" link2="link_6" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent"/>
|
||||||
|
<disable_collisions link1="link_2" link2="link_4" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_2" link2="link_5" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_2" link2="link_6" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent"/>
|
||||||
|
<disable_collisions link1="link_3" link2="link_5" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_3" link2="link_6" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent"/>
|
||||||
|
<disable_collisions link1="link_4" link2="link_6" reason="Never"/>
|
||||||
|
<disable_collisions link1="link_5" link2="link_6" reason="Adjacent"/>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
Loading…
Reference in a new issue