initial_joint_controller is now set depending on use_fake_hardware flag and not a seperate flag
This commit is contained in:
parent
79aa262153
commit
2fa4387147
@ -64,7 +64,7 @@ ros2 launch ur_robotiq_moveit_config ur_robotiq_moveit.launch.py use_fake_hardwa
|
||||
### use_fake_hardware:=true
|
||||
Terminal 1.:
|
||||
```bash
|
||||
ros2 launch ur_robotiq_description ur_robotiq_control.launch.py robot_ip:=aaa.bbb.ccc.ddd use_fake_hardware:=true launch_rviz:=false initial_joint_controller:=joint_trajectory_controller
|
||||
ros2 launch ur_robotiq_description ur_robotiq_control.launch.py robot_ip:=aaa.bbb.ccc.ddd use_fake_hardware:=true launch_rviz:=false
|
||||
```
|
||||
Terminal 2.:
|
||||
```bash
|
||||
|
@ -25,7 +25,6 @@ def launch_setup(context, *args, **kwargs):
|
||||
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
|
||||
fake_sensor_commands = LaunchConfiguration("fake_sensor_commands")
|
||||
controller_spawner_timeout = LaunchConfiguration("controller_spawner_timeout")
|
||||
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
|
||||
activate_joint_controller = LaunchConfiguration("activate_joint_controller")
|
||||
launch_rviz = LaunchConfiguration("launch_rviz")
|
||||
headless_mode = LaunchConfiguration("headless_mode")
|
||||
@ -170,6 +169,11 @@ def launch_setup(context, *args, **kwargs):
|
||||
|
||||
robot_description = {"robot_description": robot_description_content}
|
||||
|
||||
if use_fake_hardware.perform(context):
|
||||
initial_joint_controller = "joint_trajectory_controller"
|
||||
else:
|
||||
initial_joint_controller = "scaled_joint_trajectory_controller"
|
||||
|
||||
initial_joint_controllers = PathJoinSubstitution(
|
||||
[FindPackageShare(description_package), "config", controllers_file]
|
||||
)
|
||||
@ -481,13 +485,7 @@ def generate_launch_description():
|
||||
description="Timeout used when spawning controllers.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"initial_joint_controller",
|
||||
default_value="scaled_joint_trajectory_controller",
|
||||
description="Initially loaded robot controller.",
|
||||
)
|
||||
)
|
||||
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"activate_joint_controller",
|
||||
|
Loading…
Reference in New Issue
Block a user