nbv_sim/launch/panda.launch

25 lines
976 B
Plaintext
Raw Normal View History

2021-09-09 13:26:01 +02:00
<?xml version="1.0" ?>
<launch>
<arg name="robot_ip" default="172.16.0.2" />
2021-11-19 18:04:54 +01:00
<arg name="load_gripper" default="true" />
2021-09-09 13:26:01 +02:00
2021-11-19 18:04:54 +01:00
<!-- Panda control nodes -->
2021-11-24 17:03:14 +01:00
<include file="$(find franka_control)/launch/franka_control.launch">
2021-11-19 18:04:54 +01:00
<arg name="robot_ip" value="$(arg robot_ip)" />
2021-11-24 17:03:14 +01:00
<arg name="load_gripper" value="$(arg load_gripper)" />
2021-11-19 18:04:54 +01:00
</include>
<!-- Controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="--stopped position_joint_trajectory_controller cartesian_velocity_controller"/>
<!-- Camera -->
2021-09-09 13:26:01 +02:00
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
<arg name="enable_pointcloud" value="true" />
<arg name="publish_tf" value="false" />
</include>
2021-11-24 17:03:14 +01:00
<!-- Hand-eye calibration -->
<node pkg="tf2_ros" type="static_transform_publisher" name="to_camera" args="0.108, -0.019, 0.052 0.000, 0.000, 0.720, 0.694 panda_hand camera_depth_optical_frame" />
2021-09-09 13:26:01 +02:00
</launch>