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

Update code with recent change in ros2_control #81

Merged
merged 2 commits into from
Jun 16, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
9 changes: 7 additions & 2 deletions gazebo_ros2_control_demos/config/cartpole_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,16 @@ controller_manager:
joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

joint_state_controller:
type: joint_state_controller/JointStateController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller:
ros__parameters:
joints:
- slider_to_cart
interface_name: position
command_interfaces:
- position
state_interfaces:
- position
- velocity
10 changes: 8 additions & 2 deletions gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,16 @@ controller_manager:
effort_controllers:
type: effort_controllers/JointGroupEffortController

joint_state_controller:
type: joint_state_controller/JointStateController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

effort_controllers:
ros__parameters:
joints:
- slider_to_cart
command_interfaces:
- effort
state_interfaces:
- position
- velocity
- effort
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,15 @@ controller_manager:
velocity_controller:
type: velocity_controllers/JointGroupVelocityController

joint_state_controller:
type: joint_state_controller/JointStateController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

velocity_controller:
ros__parameters:
joints:
- slider_to_cart
command_interfaces:
- velocity
state_interfaces:
- position
- velocity
Original file line number Diff line number Diff line change
Expand Up @@ -57,12 +57,13 @@ def generate_launch_description():
output='screen')

load_joint_state_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'joint_state_controller'],
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start',
'joint_state_broadcaster'],
output='screen'
)

load_effort_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'effort_controllers'],
load_joint_trajectory_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', 'effort_controllers'],
output='screen'
)

Expand All @@ -76,7 +77,7 @@ def generate_launch_description():
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=load_joint_state_controller,
on_exit=[load_effort_controller],
on_exit=[load_joint_trajectory_controller],
)
),
gazebo,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,12 +57,13 @@ def generate_launch_description():
output='screen')

load_joint_state_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'joint_state_controller'],
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start',
'joint_state_broadcaster'],
output='screen'
)

load_joint_trajectory_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'joint_trajectory_controller'],
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', 'joint_trajectory_controller'],
output='screen'
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,12 +56,13 @@ def generate_launch_description():
output='screen')

load_joint_state_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'joint_state_controller'],
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start',
'joint_state_broadcaster'],
output='screen'
)

load_velocity_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'velocity_controller'],
load_joint_trajectory_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'start', 'velocity_controller'],
output='screen'
)

Expand All @@ -75,7 +76,7 @@ def generate_launch_description():
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=load_joint_state_controller,
on_exit=[load_velocity_controller],
on_exit=[load_joint_trajectory_controller],
)
),
gazebo,
Expand Down