diff --git a/ign_ros2_control_demos/config/cartpole_controller_effort.yaml b/ign_ros2_control_demos/config/cartpole_controller_effort.yaml index 54b0be31..920e4651 100644 --- a/ign_ros2_control_demos/config/cartpole_controller_effort.yaml +++ b/ign_ros2_control_demos/config/cartpole_controller_effort.yaml @@ -2,19 +2,13 @@ controller_manager: ros__parameters: update_rate: 1000 # Hz - effort_controllers: + effort_controller: type: effort_controllers/JointGroupEffortController joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster -effort_controllers: +effort_controller: ros__parameters: joints: - slider_to_cart - command_interfaces: - - effort - state_interfaces: - - position - - velocity - - effort diff --git a/ign_ros2_control_demos/config/cartpole_controller_velocity.yaml b/ign_ros2_control_demos/config/cartpole_controller_velocity.yaml index 8d6b6ab0..7215d760 100644 --- a/ign_ros2_control_demos/config/cartpole_controller_velocity.yaml +++ b/ign_ros2_control_demos/config/cartpole_controller_velocity.yaml @@ -15,11 +15,6 @@ velocity_controller: ros__parameters: joints: - slider_to_cart - command_interfaces: - - velocity - state_interfaces: - - position - - velocity imu_sensor_broadcaster: ros__parameters: diff --git a/ign_ros2_control_demos/examples/example_effort.cpp b/ign_ros2_control_demos/examples/example_effort.cpp index 0c2dcf1b..d6fbaa9e 100644 --- a/ign_ros2_control_demos/examples/example_effort.cpp +++ b/ign_ros2_control_demos/examples/example_effort.cpp @@ -26,7 +26,7 @@ int main(int argc, char * argv[]) std::make_shared("effort_test_node"); auto publisher = node->create_publisher( - "/effort_controllers/commands", 10); + "/effort_controller/commands", 10); RCLCPP_INFO(node->get_logger(), "node created"); diff --git a/ign_ros2_control_demos/launch/cart_example_effort.launch.py b/ign_ros2_control_demos/launch/cart_example_effort.launch.py index 29031401..3953494e 100644 --- a/ign_ros2_control_demos/launch/cart_example_effort.launch.py +++ b/ign_ros2_control_demos/launch/cart_example_effort.launch.py @@ -66,8 +66,8 @@ def generate_launch_description(): output='screen' ) - load_joint_trajectory_controller = ExecuteProcess( - cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'effort_controllers'], + load_joint_effort_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'effort_controller'], output='screen' ) @@ -87,7 +87,7 @@ def generate_launch_description(): RegisterEventHandler( event_handler=OnProcessExit( target_action=load_joint_state_broadcaster, - on_exit=[load_joint_trajectory_controller], + on_exit=[load_joint_effort_controller], ) ), node_robot_state_publisher,