@ -87,13 +87,6 @@ def generate_launch_description():
ompl_planning_pipeline_config ,
kinematics_yaml ] )
# TODO(JafarAbdi): We don't need this since the base is mobile
# Static TF
static_tf = Node ( package = ' tf2_ros ' ,
executable = ' static_transform_publisher ' ,
name = ' static_transform_publisher ' ,
output = ' log ' ,
arguments = [ ' 0.0 ' , ' 0.0 ' , ' 0.0 ' , ' 0.0 ' , ' 0.0 ' , ' 0.0 ' , ' odom ' , ' base_link ' ] )
# Publish TF
robot_state_publisher = Node ( package = ' robot_state_publisher ' ,
@ -116,4 +109,5 @@ def generate_launch_description():
for controller in [ ' stretch_arm_controller ' , ' gripper_controller ' ] :
load_controllers + = [ ExecuteProcess ( cmd = [ ' ros2 control load_configure_controller ' , controller ] , shell = True , output = ' screen ' , on_exit = [ ExecuteProcess ( cmd = [ ' ros2 control switch_controllers --start-controllers ' , controller ] , shell = True , output = ' screen ' ) ] ) ]
return LaunchDescription ( [ rviz_node , static_tf , robot_state_publisher , run_move_group_node , fake_joint_driver_node ] + load_controllers )
return LaunchDescription ( [ rviz_node , robot_state_publisher , run_move_group_node , fake_joint_driver_node ] + load_controllers )