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

Debug launch and yaml #1

Merged
merged 6 commits into from
Jun 12, 2021
Merged
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
63 changes: 55 additions & 8 deletions ur10_description/config/gazebo_controllers.yaml
Original file line number Diff line number Diff line change
@@ -1,22 +1,69 @@
# ur10:
# # Publish all joint states -----------------------------------
# joint_state_controller:
# type: joint_state_controller/JointStateController
# publish_rate: 50

controller_manager:
ros__parameters:
update_rate: 100 # Hz
#update_rate: 100 # Hz
#210611 if NOT set, ur10 dangles down with gravity
#TODO test other values
#update_rate: 1000 # Hz =Gazebo

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
publish_rate: 50
write_op_modes:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint

joint_state_controller:
type: joint_state_controller/JointStateController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
publish_rate: 50
write_op_modes:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint

joint_trajectory_controller:
ros__parameters:
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
write_op_modes:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
interface_name: position
state_publish_rate: 50.0
action_monitor_rate: 20.0
#state_publish_rate: 25.0
action_monitor_rate: 20.0
61 changes: 31 additions & 30 deletions ur10_gazebo/launch/ur10_gazebo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,39 +84,40 @@ def generate_launch_description():
arguments=['-topic', 'robot_description',
'-entity', 'ur10'],
output='screen')

load_joint_state_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'joint_state_controller'],
output='screen'
)

load_joint_trajectory_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'joint_trajectory_controller'],
output='screen'
)

# Static TF
#static_tf = Node(package='tf2_ros',
# executable='static_transform_publisher',
# name='static_transform_publisher',
# output='log',
# arguments=['0.0', '0.0', '0.65', '0.0', '0.0', '0.0', 'world', 'ur_base'])
#210611
# load_joint_state_controller = ExecuteProcess(
# cmd=['ros2', 'control', 'load_start_controller', 'joint_state_controller'],
# output='screen'
# )

# load_joint_trajectory_controller = ExecuteProcess(
# cmd=['ros2', 'control', 'load_start_controller', 'joint_trajectory_controller'],
# output='screen'
# )

#Static TF
static_tf = Node(package='tf2_ros',
executable='static_transform_publisher',
name='static_transform_publisher',
output='log',
arguments=['0.0', '0.0', '0.65', '0.0', '0.0', '0.0', 'world', 'ur_base'])

return LaunchDescription([
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=spawn_entity,
on_exit=[load_joint_state_controller],
)
),
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=load_joint_state_controller,
on_exit=[load_joint_trajectory_controller],
)
),
#210611
# RegisterEventHandler(
# event_handler=OnProcessExit(
# target_action=spawn_entity,
# on_exit=[load_joint_state_controller],
# )
# ),
# RegisterEventHandler(
# event_handler=OnProcessExit(
# target_action=load_joint_state_controller,
# on_exit=[load_joint_trajectory_controller],
# )
# ),
gazebo,
node_robot_state_publisher,
#static_tf,
static_tf,
spawn_entity
])
4 changes: 2 additions & 2 deletions ur10_moveit_config/config/ur10_ros_controllers.yaml
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
controller_manager:
ros__parameters:
update_rate: 100 # Hz
#update_rate: 100 # Hz
#update_rate: 1000 # Hz =Gazebo

ur10_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController

joint_state_controller:
type: joint_state_controller/JointStateController


ur10_arm_controller:
ros__parameters:
joints:
Expand Down