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

Remap joint states instead of re-publish #192

Open
wants to merge 2 commits into
base: develop
Choose a base branch
from
Open
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
15 changes: 4 additions & 11 deletions franka_control/launch/franka_control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@

<param name="robot_description" command="$(find xacro)/xacro $(find franka_description)/robots/panda_arm.urdf.xacro hand:=$(arg load_gripper)" />

<!-- Remap both, arm and gripper joint states to default ROS topic joint_states -->
<remap from="franka_state_controller/joint_states" to="joint_states" />
<remap from="franka_gripper/joint_states" to="joint_states" />

<include file="$(find franka_gripper)/launch/franka_gripper.launch" if="$(arg load_gripper)">
<arg name="robot_ip" value="$(arg robot_ip)" />
</include>
Expand All @@ -17,15 +21,4 @@
<rosparam command="load" file="$(find franka_control)/config/default_controllers.yaml" />
<node name="state_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="franka_state_controller"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen"/>
<node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen">
<rosparam if="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states, franka_gripper/joint_states] </rosparam>
<rosparam unless="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states] </rosparam>
<param name="rate" value="30"/>
</node>
<node name="joint_state_desired_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen">
<rosparam if="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states_desired, franka_gripper/joint_states] </rosparam>
<rosparam unless="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states_desired] </rosparam>
<param name="rate" value="30"/>
<remap from="/joint_states" to="/joint_states_desired" />
</node>
</launch>
12 changes: 3 additions & 9 deletions franka_gazebo/launch/panda.launch
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,9 @@
<arg name="paused" value="true"/>
<arg name="gui" value="$(eval not arg('headless'))"/>
<arg name="use_sim_time" value="true"/>
<!-- Remap both, arm and gripper joint states to default ROS topic joint_states -->
<remap from="franka_state_controller/joint_states" to="joint_states" />
<remap from="franka_gripper/joint_states" to="joint_states" />
</include>

<param name="robot_description"
Expand Down Expand Up @@ -76,15 +79,6 @@
/>

<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher">
<rosparam param="source_list">[franka_state_controller/joint_states, franka_gripper/joint_states] </rosparam>
<param name="rate" value="30"/>
</node>
<node name="joint_state_desired_publisher" type="joint_state_publisher" pkg="joint_state_publisher">
<rosparam param="source_list">[franka_state_controller/joint_states_desired, franka_gripper/joint_states] </rosparam>
<param name="rate" value="30"/>
<remap from="joint_states" to="joint_states_desired" />
</node>

<!-- Start only if cartesian_impedance_example_controller -->
<node name="interactive_marker"
Expand Down