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

Cleanup controller config #232

Merged
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
10 changes: 2 additions & 8 deletions gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion gazebo_ros2_control_demos/examples/example_effort.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ int main(int argc, char * argv[])
node = std::make_shared<rclcpp::Node>("effort_test_node");

auto publisher = node->create_publisher<std_msgs::msg::Float64MultiArray>(
"/effort_controllers/commands", 10);
"/effort_controller/commands", 10);

RCLCPP_INFO(node->get_logger(), "node created");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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'
)

Expand Down