Skip to content

Commit

Permalink
chore: Update launch and config files with motion control handle and …
Browse files Browse the repository at this point in the history
…robot description
  • Loading branch information
lucabeber committed Jun 12, 2024
1 parent 684f95d commit d17311c
Show file tree
Hide file tree
Showing 5 changed files with 16 additions and 10 deletions.
12 changes: 7 additions & 5 deletions lbr_bringup/launch/real.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,9 @@ def launch_setup(context: LaunchContext) -> List[LaunchDescriptionEntity]:
ld.add_action(robot_state_publisher)

# ros2 control node
ros2_control_node = LBRROS2ControlMixin.node_ros2_control()
ros2_control_node = LBRROS2ControlMixin.node_ros2_control(
robot_description=robot_description,
)
ld.add_action(ros2_control_node)

# joint state broad caster and controller on ros2 control node start
Expand All @@ -41,9 +43,9 @@ def launch_setup(context: LaunchContext) -> List[LaunchDescriptionEntity]:
lbr_state_broadcaster = LBRROS2ControlMixin.node_controller_spawner(
controller="lbr_state_broadcaster"
)
lbr_motion_control_handle = LBRROS2ControlMixin.node_controller_spawner(
controller="motion_control_handle"
)
# lbr_motion_control_handle = LBRROS2ControlMixin.node_controller_spawner(
# controller="motion_control_handle"
# )
controller = LBRROS2ControlMixin.node_controller_spawner(
controller=LaunchConfiguration("ctrl")
)
Expand All @@ -56,7 +58,7 @@ def launch_setup(context: LaunchContext) -> List[LaunchDescriptionEntity]:
force_torque_broadcaster,
lbr_state_broadcaster,
controller,
lbr_motion_control_handle,
# lbr_motion_control_handle,
],
)
)
Expand Down
4 changes: 3 additions & 1 deletion lbr_bringup/launch/system_interface.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,9 @@ def generate_launch_description() -> LaunchDescription:
use_sim_time=False,
)
ld.add_action(robot_state_publisher)
ros2_control_node = LBRSystemInterface.node_ros2_control()
ros2_control_node = LBRSystemInterface.node_ros2_control(
robot_description=robot_description,
)
ld.add_action(ros2_control_node)
joint_state_broadcaster = LBRSystemInterface.node_controller_spawner(
controller="joint_state_broadcaster"
Expand Down
2 changes: 2 additions & 0 deletions lbr_bringup/launch_mixins/lbr_ros2_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ def arg_use_sim_time() -> DeclareLaunchArgument:

@staticmethod
def node_ros2_control(
robot_description: Dict[str, str],
robot_name: Optional[Union[LaunchConfiguration, str]] = LaunchConfiguration(
"robot_name", default="lbr"
),
Expand All @@ -59,6 +60,7 @@ def node_ros2_control(
package="controller_manager",
executable="ros2_control_node",
parameters=[
robot_description,
{"use_sim_time": False},
PathJoinSubstitution(
[
Expand Down
2 changes: 1 addition & 1 deletion lbr_ros2_control/config/lbr_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
# managers regardless of their namespace. Usefull in multi-robot setups.
/**/controller_manager:
ros__parameters:
update_rate: 100
update_rate: 500

# ROS 2 control broadcasters
joint_state_broadcaster:
Expand Down
6 changes: 3 additions & 3 deletions lbr_ros2_control/config/lbr_system_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
hardware:
fri_client_sdk: # the fri_client_sdk version is used to create the correct state interfaces lbr_system_interface.xacro
major_version: 1
minor_version: 15
client_command_mode: position # the command mode specifies the user-sent commands. Available: [position, torque, wrench]
minor_version: 17
client_command_mode: torque # the command mode specifies the user-sent commands. Available: [position, torque, wrench]
port_id: 30200 # port id for the UDP communication. Useful in multi-robot setups
remote_host: INADDR_ANY # the expected robot IP address. INADDR_ANY will accept any incoming connection
rt_prio: 80 # real-time priority for the control loop
Expand All @@ -16,7 +16,7 @@ hardware:
command_guard_variant: default # if requested position / velocities beyond limits, CommandGuard will be triggered and shut the connection. Available: [default, safe_stop]
external_torque_cutoff_frequency: 10 # low-pass filter for the external joint torque measurements [Hz]
measured_torque_cutoff_frequency: 10 # low-pass filter for the joint torque measurements [Hz]
open_loop: true # KUKA works the best in open_loop control mode
open_loop: false # KUKA works the best in open_loop control mode

estimated_ft_sensor: # estimates the external force-torque from the external joint torque values
chain_root: link_0
Expand Down

0 comments on commit d17311c

Please sign in to comment.