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

Gazebo effort controllers #619

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
2 changes: 1 addition & 1 deletion ur10_moveit_config/launch/moveit_planning_execution.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="debug" default="false" />

<!-- Remap follow_joint_trajectory -->
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/pos_joint_traj_controller/follow_joint_trajectory"/>
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/eff_joint_traj_controller/follow_joint_trajectory"/>

<!-- Launch moveit -->
<include file="$(find ur10_moveit_config)/launch/move_group.launch">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="debug" default="false" />

<!-- Remap follow_joint_trajectory -->
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/pos_joint_traj_controller/follow_joint_trajectory"/>
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/eff_joint_traj_controller/follow_joint_trajectory"/>

<!-- Launch moveit -->
<include file="$(find ur10e_moveit_config)/launch/move_group.launch">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="debug" default="false" />

<!-- Remap follow_joint_trajectory -->
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/pos_joint_traj_controller/follow_joint_trajectory"/>
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/eff_joint_traj_controller/follow_joint_trajectory"/>

<!-- Launch moveit -->
<include file="$(find ur16e_moveit_config)/launch/move_group.launch">
Expand Down
2 changes: 1 addition & 1 deletion ur3_moveit_config/launch/moveit_planning_execution.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="debug" default="false" />

<!-- Remap follow_joint_trajectory -->
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/pos_joint_traj_controller/follow_joint_trajectory"/>
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/eff_joint_traj_controller/follow_joint_trajectory"/>

<!-- Launch moveit -->
<include file="$(find ur3_moveit_config)/launch/move_group.launch">
Expand Down
2 changes: 1 addition & 1 deletion ur3e_moveit_config/launch/moveit_planning_execution.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="debug" default="false" />

<!-- Remap follow_joint_trajectory -->
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/pos_joint_traj_controller/follow_joint_trajectory"/>
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/eff_joint_traj_controller/follow_joint_trajectory"/>

<!-- Launch moveit -->
<include file="$(find ur3e_moveit_config)/launch/move_group.launch">
Expand Down
2 changes: 1 addition & 1 deletion ur5_moveit_config/launch/moveit_planning_execution.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="debug" default="false" />

<!-- Remap follow_joint_trajectory -->
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/pos_joint_traj_controller/follow_joint_trajectory"/>
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/eff_joint_traj_controller/follow_joint_trajectory"/>

<!-- Launch moveit -->
<include file="$(find ur5_moveit_config)/launch/move_group.launch">
Expand Down
2 changes: 1 addition & 1 deletion ur5e_moveit_config/launch/moveit_planning_execution.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="debug" default="false" />

<!-- Remap follow_joint_trajectory -->
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/pos_joint_traj_controller/follow_joint_trajectory"/>
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/eff_joint_traj_controller/follow_joint_trajectory"/>

<!-- Launch moveit -->
<include file="$(find ur5e_moveit_config)/launch/move_group.launch">
Expand Down
15 changes: 11 additions & 4 deletions ur_gazebo/config/ur10_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,22 @@ joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 125

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
eff_joint_traj_controller:
type: effort_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
gains: # Required because we're controlling an effort interface
shoulder_pan_joint: {p: 20000, d: 500, i: 10, i_clamp: 1}
shoulder_lift_joint: {p: 20000, d: 500, i: 10, i_clamp: 1}
elbow_joint: {p: 20000, d: 500, i: 10, i_clamp: 1}
wrist_1_joint: {p: 500, d: 10, i: 1, i_clamp: 1}
wrist_2_joint: {p: 500, d: 10, i: 1, i_clamp: 1}
wrist_3_joint: {p: 10, d: 0.1, i: 0, i_clamp: 1}
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
Expand All @@ -24,6 +31,6 @@ pos_joint_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joint_group_eff_controller:
type: effort_controllers/JointGroupEffortController
joints: *robot_joints
15 changes: 11 additions & 4 deletions ur_gazebo/config/ur10e_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,22 @@ joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 500

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
eff_joint_traj_controller:
type: effort_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
gains: # Required because we're controlling an effort interface
shoulder_pan_joint: {p: 20000, d: 100, i: 10, i_clamp: 1}
shoulder_lift_joint: {p: 20000, d: 100, i: 20, i_clamp: 1}
elbow_joint: {p: 10000, d: 100, i: 10, i_clamp: 1}
wrist_1_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_2_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_3_joint: {p: 10, d: 0.1, i: 0, i_clamp: 1}
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
Expand All @@ -24,6 +31,6 @@ pos_joint_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joint_group_eff_controller:
type: effort_controllers/JointGroupEffortController
joints: *robot_joints
15 changes: 11 additions & 4 deletions ur_gazebo/config/ur16e_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,22 @@ joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 500

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
eff_joint_traj_controller:
type: effort_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
gains: # Required because we're controlling an effort interface
shoulder_pan_joint: {p: 20000, d: 500, i: 10, i_clamp: 1}
shoulder_lift_joint: {p: 20000, d: 500, i: 10, i_clamp: 1}
elbow_joint: {p: 10000, d: 200, i: 10, i_clamp: 1}
wrist_1_joint: {p: 500, d: 10, i: 1, i_clamp: 1}
wrist_2_joint: {p: 500, d: 10, i: 1, i_clamp: 1}
wrist_3_joint: {p: 100, d: 0.1, i: 0, i_clamp: 1}
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
Expand All @@ -24,6 +31,6 @@ pos_joint_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joint_group_eff_controller:
type: effort_controllers/JointGroupEffortController
joints: *robot_joints
15 changes: 11 additions & 4 deletions ur_gazebo/config/ur3_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,22 @@ joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 125

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
eff_joint_traj_controller:
type: effort_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
gains: # Required because we're controlling an effort interface
shoulder_pan_joint: {p: 2000, d: 20, i: 1, i_clamp: 1}
shoulder_lift_joint: {p: 6000, d: 40, i: 1, i_clamp: 1}
elbow_joint: {p: 2000, d: 20, i: 1, i_clamp: 1}
wrist_1_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_2_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_3_joint: {p: 10, d: 0.1, i: 0, i_clamp: 1}
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
Expand All @@ -24,6 +31,6 @@ pos_joint_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joint_group_eff_controller:
type: effort_controllers/JointGroupEffortController
joints: *robot_joints
15 changes: 11 additions & 4 deletions ur_gazebo/config/ur3e_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,22 @@ joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 500

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
eff_joint_traj_controller:
type: effort_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
gains: # Required because we're controlling an effort interface
shoulder_pan_joint: {p: 2000, d: 20, i: 1, i_clamp: 1}
shoulder_lift_joint: {p: 6000, d: 40, i: 1, i_clamp: 1}
elbow_joint: {p: 2000, d: 20, i: 1, i_clamp: 1}
wrist_1_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_2_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_3_joint: {p: 10, d: 0.1, i: 0, i_clamp: 1}
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
Expand All @@ -24,6 +31,6 @@ pos_joint_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joint_group_eff_controller:
type: effort_controllers/JointGroupEffortController
joints: *robot_joints
15 changes: 11 additions & 4 deletions ur_gazebo/config/ur5_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,22 @@ joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 125

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
eff_joint_traj_controller:
type: effort_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
gains: # Required because we're controlling an effort interface
shoulder_pan_joint: {p: 4000, d: 200, i: 1, i_clamp: 1}
shoulder_lift_joint: {p: 10000, d: 200, i: 1, i_clamp: 1}
elbow_joint: {p: 2000, d: 20, i: 1, i_clamp: 1}
wrist_1_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_2_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_3_joint: {p: 10, d: 0.1, i: 0, i_clamp: 1}
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
Expand All @@ -24,6 +31,6 @@ pos_joint_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joint_group_eff_controller:
type: effort_controllers/JointGroupEffortController
joints: *robot_joints
15 changes: 11 additions & 4 deletions ur_gazebo/config/ur5e_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,22 @@ joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 500

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
eff_joint_traj_controller:
type: effort_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
gains: # Required because we're controlling an effort interface
shoulder_pan_joint: {p: 4000, d: 200, i: 1, i_clamp: 1}
shoulder_lift_joint: {p: 10000, d: 200, i: 1, i_clamp: 1}
elbow_joint: {p: 2000, d: 20, i: 1, i_clamp: 1}
wrist_1_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_2_joint: {p: 500, d: 1, i: 1, i_clamp: 1}
wrist_3_joint: {p: 10, d: 0.1, i: 0, i_clamp: 1}
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
Expand All @@ -24,6 +31,6 @@ pos_joint_traj_controller:
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joint_group_eff_controller:
type: effort_controllers/JointGroupEffortController
joints: *robot_joints
2 changes: 1 addition & 1 deletion ur_gazebo/launch/inc/load_ur.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
<arg name="visual_params" doc="YAML file containing the visual model of the robots"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />
Expand Down
2 changes: 1 addition & 1 deletion ur_gazebo/launch/inc/load_ur10.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="visual_params" default="$(find ur_description)/config/ur10/visual_parameters.yaml"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />
Expand Down
2 changes: 1 addition & 1 deletion ur_gazebo/launch/inc/load_ur10e.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="visual_params" default="$(find ur_description)/config/ur10e/visual_parameters.yaml"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />
Expand Down
2 changes: 1 addition & 1 deletion ur_gazebo/launch/inc/load_ur16e.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="visual_params" default="$(find ur_description)/config/ur16e/visual_parameters.yaml"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />
Expand Down
2 changes: 1 addition & 1 deletion ur_gazebo/launch/inc/load_ur3.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="visual_params" default="$(find ur_description)/config/ur3/visual_parameters.yaml"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />
Expand Down
2 changes: 1 addition & 1 deletion ur_gazebo/launch/inc/load_ur3e.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="visual_params" default="$(find ur_description)/config/ur3e/visual_parameters.yaml"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />
Expand Down
2 changes: 1 addition & 1 deletion ur_gazebo/launch/inc/load_ur5.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="visual_params" default="$(find ur_description)/config/ur5/visual_parameters.yaml"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />
Expand Down
2 changes: 1 addition & 1 deletion ur_gazebo/launch/inc/load_ur5e.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="visual_params" default="$(find ur_description)/config/ur5e/visual_parameters.yaml"/>

<!--Common parameters -->
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface" doc="The hardware_interface to expose for each joint in the simulated robot (one of: [PositionJointInterface, VelocityJointInterface, EffortJointInterface])"/>
<arg name="safety_limits" default="false" doc="If True, enable the safety limits controller"/>
<arg name="safety_pos_margin" default="0.15" doc="The lower/upper limits in the safety controller" />
<arg name="safety_k_position" default="20" doc="Used to set k position in the safety controller" />
Expand Down
Loading