Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixing errors in the "Perception Driven Manipulation" ROS2 demo. #418

Open
wants to merge 2 commits into
base: humble
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -151,5 +151,6 @@
<xacro:workcell_element name="cover_part2" parent="world_frame"
length="0.121" width="0.260" height="0.14" offset_x="-0.012" offset_y="-0.465"/>
</xacro:macro>

<!-- end of workcell part2 components macro -->
</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -208,6 +208,7 @@
<disable_collisions link1="shoulder_link" link2="table_base2" reason="Never" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="ur5_stand" reason="Never" />
<disable_collisions link1="shoulder_link" link2="base_link_inertia" reason="Never" />
<disable_collisions link1="table_base2" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="table_base2" link2="ur5_stand" reason="Adjacent" />
<disable_collisions link1="tcp_frame" link2="wrist_1_link" reason="Never" />
Expand Down
Original file line number Diff line number Diff line change
@@ -1,32 +1,10 @@
#controller_manager:
# update_rate: 100 # Hz
# controller_list:
# - name: manipulator_joint_trajectory_controller
# type: joint_trajectory_controller/JointTrajectoryController
# - name: joint_state_broadcaster
# type: joint_state_broadcaster/JointStateController
#
#manipulator_joint_trajectory_controller:
# command_interfaces:
# - position
# state_interfaces:
# - position
# - velocity
# joints:
# - elbow_joint
# - shoulder_lift_joint
# - shoulder_pan_joint
# - wrist_1_joint
# - wrist_2_joint
# - wrist_3_joint
#
controller_manager:
ros__parameters:
update_rate: 600 # Hz
manipulator_joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateController
type: joint_state_broadcaster/JointStateBroadcaster
io_and_status_controller:
type: ur_controllers/GPIOController

Expand All @@ -53,5 +31,5 @@ manipulator_joint_trajectory_controller:
goal_time: 0.0
joint_state_broadcaster:
ros__parameters:
type: joint_state_broadcaster/JointStateController
type: joint_state_broadcaster/JointStateBroadcaster

Original file line number Diff line number Diff line change
Expand Up @@ -208,6 +208,7 @@
<disable_collisions link1="shoulder_link" link2="table_base2" reason="Never" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="ur5_stand" reason="Never" />
<disable_collisions link1="shoulder_link" link2="base_link_inertia" reason="Never" />
<disable_collisions link1="table_base2" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="table_base2" link2="ur5_stand" reason="Adjacent" />
<disable_collisions link1="tcp_frame" link2="wrist_1_link" reason="Never" />
Expand Down