diff --git a/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml b/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml index 8ea3c67c..baf14bc3 100644 --- a/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml +++ b/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml @@ -2,19 +2,13 @@ controller_manager: ros__parameters: update_rate: 100 # 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/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml b/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml index 6a9e240d..cea5cc9e 100644 --- a/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml +++ b/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml @@ -15,11 +15,7 @@ velocity_controller: ros__parameters: joints: - slider_to_cart - command_interfaces: - - velocity - state_interfaces: - - position - - velocity + imu_sensor_broadcaster: ros__parameters: sensor_name: cart_imu_sensor diff --git a/gazebo_ros2_control_demos/examples/example_effort.cpp b/gazebo_ros2_control_demos/examples/example_effort.cpp index dd4bff8b..ef76a603 100644 --- a/gazebo_ros2_control_demos/examples/example_effort.cpp +++ b/gazebo_ros2_control_demos/examples/example_effort.cpp @@ -29,7 +29,7 @@ int main(int argc, char * argv[]) node = 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/gazebo_ros2_control_demos/launch/cart_example_effort.launch.py b/gazebo_ros2_control_demos/launch/cart_example_effort.launch.py index 3e6c91b8..95caf297 100644 --- a/gazebo_ros2_control_demos/launch/cart_example_effort.launch.py +++ b/gazebo_ros2_control_demos/launch/cart_example_effort.launch.py @@ -63,7 +63,7 @@ def generate_launch_description(): ) load_joint_trajectory_controller = ExecuteProcess( - cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'effort_controllers'], + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'effort_controller'], output='screen' )