Skip to content

Commit d8b43d8

Browse files
authored
Deprecation warnings fix jtc (#779)
1 parent 2723e0d commit d8b43d8

File tree

3 files changed

+3
-3
lines changed

3 files changed

+3
-3
lines changed

example_1/bringup/config/rrbot_jtc.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ joint_trajectory_position_controller:
1515
action_monitor_rate: 20.0 # Defaults to 20
1616

1717
allow_partial_joints_goal: false # Defaults to false
18-
open_loop_control: true
18+
interpolate_from_desired_state: true
1919
allow_integration_in_goal_trajectories: true
2020
constraints:
2121
stopped_velocity_tolerance: 0.01 # Defaults to 0.01

example_15/bringup/config/multi_controller_manager_rrbot_generic_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@
4949
action_monitor_rate: 20.0 # Defaults to 20
5050

5151
allow_partial_joints_goal: false # Defaults to false
52-
open_loop_control: true
52+
interpolate_from_desired_state: true
5353
allow_integration_in_goal_trajectories: true
5454
constraints:
5555
stopped_velocity_tolerance: 0.01 # Defaults to 0.01

example_15/bringup/config/rrbot_namespace_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
action_monitor_rate: 20.0 # Defaults to 20
3333

3434
allow_partial_joints_goal: false # Defaults to false
35-
open_loop_control: true
35+
interpolate_from_desired_state: true
3636
allow_integration_in_goal_trajectories: true
3737
constraints:
3838
stopped_velocity_tolerance: 0.01 # Defaults to 0.01

0 commit comments

Comments
 (0)