Skip to content

Commit

Permalink
Bump example to latest ros2_control(ler) syntax
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Aug 5, 2023
1 parent 53f930e commit 11e2c88
Show file tree
Hide file tree
Showing 9 changed files with 37 additions and 23 deletions.
6 changes: 3 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -699,7 +699,7 @@ ros2 launch ros2_control_demo_bringup test_forward_position_controller.launch.py

Switch controller to use `position_trajectory_controller` (`JointTrajectoryController`):
```
ros2 control switch_controllers -c /rrbot/controller_manager --stop forward_position_controller --start position_trajectory_controller
ros2 control switch_controllers -c /rrbot/controller_manager --deactivate forward_position_controller --activate position_trajectory_controller
```

Commanding the robot using `JointTrajectoryController` (name: `/rrbot/position_trajectory_controller`)
Expand Down Expand Up @@ -750,8 +750,8 @@ ros2 launch ros2_control_demo_bringup test_multi_controller_manager_forward_posi

Switch controller to use `position_trajectory_controller`s (`JointTrajectoryController`) - alternatively start main launch file with argument `robot_controller:=position_trajectory_controller`:
```
ros2 control switch_controllers -c /rrbot_1/controller_manager --stop forward_position_controller --start position_trajectory_controller
ros2 control switch_controllers -c /rrbot_2/controller_manager --stop forward_position_controller --start position_trajectory_controller
ros2 control switch_controllers -c /rrbot_1/controller_manager --deactivate forward_position_controller --activate position_trajectory_controller
ros2 control switch_controllers -c /rrbot_2/controller_manager --deactivate forward_position_controller --activate position_trajectory_controller
```

Commanding the robot using `JointTrajectoryController` (`position_trajectory_controller`):
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
/rrbot_1/publisher_forward_position_controller:
ros__parameters:

controller_name: "rrbot_1/forward_position_controller"

publish_topic: "forward_position_controller/commands"
wait_sec_between_publish: 5

goal_names: ["pos1", "pos2", "pos3", "pos4"]
Expand All @@ -14,7 +15,7 @@
/rrbot_2/publisher_forward_position_controller:
ros__parameters:

controller_name: "rrbot_2/forward_position_controller"
publish_topic: "forward_position_controller/commands"
wait_sec_between_publish: 5

goal_names: ["pos1", "pos2", "pos3", "pos4"]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,14 @@
wait_sec_between_publish: 6

goal_names: ["pos1", "pos2", "pos3", "pos4"]
pos1: [0.785, 0.785]
pos2: [0.0, 0.0]
pos3: [-0.785, -0.785]
pos4: [0.0, 0.0]
pos1:
positions: [0.785, 0.785]
pos2:
positions: [0.0, 0.0]
pos3:
positions: [-0.785, -0.785]
pos4:
positions: [0.0, 0.0]

joints:
- rrbot_1_joint1
Expand All @@ -27,10 +31,14 @@
wait_sec_between_publish: 6

goal_names: ["pos1", "pos2", "pos3", "pos4"]
pos1: [-0.785, 0.0]
pos2: [0.0, -0.785]
pos3: [+0.785, -1.57]
pos4: [+1.57, -0.785]
pos1:
positions: [-0.785, 0.0]
pos2:
positions: [0.0, -0.785]
pos3:
positions: [+0.785, -1.57]
pos4:
positions: [+1.57, -0.785]

joints:
- rrbot_2_joint1
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
publisher_forward_position_controller:
ros__parameters:

controller_name: "rrbot/forward_position_controller"
wait_sec_between_publish: 5

publish_topic: /rrbot/forward_position_controller/commands

goal_names: ["pos1", "pos2", "pos3", "pos4"]
pos1: [0.785, 0.785]
pos2: [0, 0]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,14 @@ publisher_joint_trajectory_controller:
wait_sec_between_publish: 6

goal_names: ["pos1", "pos2", "pos3", "pos4"]
pos1: [0.785, 0.785]
pos2: [0, 0]
pos3: [-0.785, -0.785]
pos4: [0, 0]
pos1:
positions: [0.785, 0.785]
pos2:
positions: [0.0, 0.0]
pos3:
positions: [-0.785, -0.785]
pos4:
positions: [0.0, 0.0]

joints:
- joint1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ def generate_launch_description():
"position_trajectory_controller",
"-c",
"/rrbot_1/controller_manager",
"--stopped",
"--inactive",
],
)

Expand All @@ -108,7 +108,7 @@ def generate_launch_description():
"position_trajectory_controller",
"-c",
"/rrbot_2/controller_manager",
"--stopped",
"--inactive",
],
)

Expand Down
2 changes: 1 addition & 1 deletion ros2_control_demo_bringup/launch/rrbot_namespace.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ def generate_launch_description():
"position_trajectory_controller",
"-c",
"/rrbot/controller_manager",
"--stopped",
"--inactive",
],
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ def generate_launch_description():
return LaunchDescription(
[
Node(
package="ros2_control_test_nodes",
package="ros2_controllers_test_nodes",
executable="publisher_forward_position_controller",
name="publisher_forward_position_controller",
parameters=[position_goals],
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ def generate_launch_description():
return LaunchDescription(
[
Node(
package="ros2_control_test_nodes",
package="ros2_controllers_test_nodes",
executable="publisher_joint_trajectory_controller",
name="publisher_joint_trajectory_controller",
parameters=[position_goals],
Expand Down

0 comments on commit 11e2c88

Please sign in to comment.