Skip to content

Commit

Permalink
feat: make code compatible with latest franka_ros version (#183)
Browse files Browse the repository at this point in the history
This commit guarantees that the `panda_gazebo` code aligns with the most
recent upstream commit (specifically
5f90395ef000e0c998fb7aff8f127b9bd3773962). Adjustments were made to the
joint position and joint effort control services to integrate with the
updated version seamlessly. In the new iteration, the panda arm joint
positions and efforts are managed through group controllers. You can
find additional insights at
frankaemika/franka_ros#181 (comment).
  • Loading branch information
rickstaa authored Nov 22, 2023
1 parent 99e98e4 commit b466168
Show file tree
Hide file tree
Showing 46 changed files with 564 additions and 915 deletions.
2 changes: 1 addition & 1 deletion franka_ros
Submodule franka_ros updated 116 files
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
# Configuration file that contains the configuration values for setting up the panda
# trajectory controllers that can control a joint effort hardware interface.
# NOTE: Equal to Franka's 'effort_joint_trajectory_controller' but with a different
# goal tolerance (see https://github.com/frankaemika/franka_ros/issues/201).
panda_arm_controller:
type: effort_controllers/JointTrajectoryController
joints:
Expand All @@ -20,7 +22,6 @@ panda_arm_controller:
panda_joint7: { p: 50, d: 5, i: 0 }
constraints:
goal_time: 0.5
stopped_velocity_tolerance: 0 # Added because of wrong PID gains see #9
panda_joint1: { goal: 0.005 }
panda_joint2: { goal: 0.005 }
panda_joint3: { goal: 0.005 }
Expand Down
23 changes: 0 additions & 23 deletions panda_gazebo/cfg/controllers/joint_effort_controllers.yaml

This file was deleted.

12 changes: 12 additions & 0 deletions panda_gazebo/cfg/controllers/joint_group_effort_controller.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# Configuration file that contains the configuration values for setting up the panda
# group effort controller.
panda_arm_joint_effort_controller:
type: effort_controllers/JointGroupEffortController
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
12 changes: 12 additions & 0 deletions panda_gazebo/cfg/controllers/joint_group_position_controller.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# Configuration file that contains the configuration values for setting up the panda
# group position controller.
panda_arm_joint_position_controller:
type: position_controllers/JointGroupPositionController
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
23 changes: 0 additions & 23 deletions panda_gazebo/cfg/controllers/joint_position_controllers.yaml

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
# Configuration file that contains the configuration values for setting up the panda
# trajectory controllers.
# NOTE: Equal to Franka's 'position_joint_trajectory_controller' but with a different
# goal tolerance (see https://github.com/frankaemika/franka_ros/issues/201).
panda_arm_controller:
type: position_controllers/JointTrajectoryController
joints:
Expand Down
4 changes: 2 additions & 2 deletions panda_gazebo/cfg/dyn_reconf/EffortControlTestDynReconf.cfg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#!/usr/bin/env python3
# NOTE: Config for changing the joint efforts.
# NOTE: Config for changing the panda arm joint efforts and gripper width and speed.
PACKAGE = "panda_gazebo"

from dynamic_reconfigure.parameter_generator_catkin import (ParameterGenerator,
Expand Down Expand Up @@ -39,4 +39,4 @@ hand.add(
)

# Generate the necessary files and exit the program.
exit(gen.generate(PACKAGE, "panda_test", "JointEffort"))
exit(gen.generate(PACKAGE, "panda_test", "JointEfforts"))
4 changes: 2 additions & 2 deletions panda_gazebo/cfg/dyn_reconf/PositionControlTestDynReconf.cfg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#!/usr/bin/env python3
# NOTE: Config for the changing the joint positions
# NOTE: Config for the changing the panda arm joint positions and gripper width and speed.
PACKAGE = "panda_gazebo"

from dynamic_reconfigure.parameter_generator_catkin import (ParameterGenerator,
Expand Down Expand Up @@ -39,4 +39,4 @@ hand.add(
)

# Generate the necessary files and exit the program.
exit(gen.generate(PACKAGE, "panda_test", "JointPosition"))
exit(gen.generate(PACKAGE, "panda_test", "JointPositions"))
8 changes: 5 additions & 3 deletions panda_gazebo/docs/source/get_started/usage.rst
Original file line number Diff line number Diff line change
Expand Up @@ -24,16 +24,18 @@ modes that can be selected using the ``control_mode`` argument:

.. Note::

You can test different control modes using the :mod:`joint_effort_dynamic_reconfigure_server` and :mod:`joint_position_dynamic_reconfigure_server` nodes.
You can test different control modes using the :mod:`joint_efforts_dynamic_reconfigure_server` and :mod:`joint_positions_dynamic_reconfigure_server` nodes.
These nodes allow you to send joint efforts and joint positions to the robot. To learn more about utilizing these dynamic reconfigure servers, refer to the
documentation of the `dynamic_reconfigure`_ and `rqt_reconfigure`_ ROS packages.

Furthermore, you can explore trajectory control using the `MoveIt! package`_. To enable this functionality, set the ``use_moveit`` launch file argument to ```true``. Once
enabled, you can control the robot through the `RViz Motion Planning`_ panel. For detailed instructions on how to use `MoveIt!`_, consult the `MoveIt! tutorials`_.
Furthermore, you can explore trajectory control using the `MoveIt! package`_ or `rqt_joint_trajectory_controller package`_. To enable `MoveIt!`, set the
``use_moveit`` launch file argument to ``true``. Once enabled, you can control the robot through the `RViz Motion Planning`_ panel. For detailed instructions on how to
use `MoveIt!`_, consult the `MoveIt! tutorials`_.

.. _dynamic_reconfigure: https://wiki.ros.org/dynamic_reconfigure
.. _rqt_reconfigure: https://wiki.ros.org/rqt_reconfigure
.. _`MoveIt! package`: https://moveit.ros.org/
.. _`rqt_joint_trajectory_controller package`: https://wiki.ros.org/rqt_joint_trajectory_controller
.. _`RViz Motion Planning`: https://ros-planning.github.io/moveit_tutorials/doc/motion_planning_rviz/motion_planning_rviz_tutorial.html
.. _`MoveIt!`: https://ros-planning.github.io/moveit_tutorials/
.. _`MoveIt! tutorials`: https://ros-planning.github.io/moveit_tutorials/
Expand Down
12 changes: 6 additions & 6 deletions panda_gazebo/launch/load_controllers.launch.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<!--Launch file loads the control parameters and controllers-->
<!--Launch file that loads the control parameters and controllers-->
<launch>
<arg name="moveit" default="true" doc="Start MoveIt"/>
<arg name="load_gripper" default="true" doc="Load the gripper"/>
Expand All @@ -18,20 +18,20 @@
<!--Load controllers-->
<!--Joint position controllers-->
<group if="$(eval arg('control_type') == 'position')">
<include file="$(find panda_gazebo)/launch/load_joint_position_controllers.launch.xml"/>
<include file="$(find panda_gazebo)/launch/load_joint_group_position_controller.launch.xml"/>
<!--Load joint_trajectory controller in stopped mode
NOTE: This enabled us to set the initial robot pose using euclidean coordinates.
-->
<include file="$(find panda_gazebo)/launch/load_position_joint_trajectory_controllers.launch.xml">
<include file="$(find panda_gazebo)/launch/load_position_joint_trajectory_controller.launch.xml">
<arg name="stopped" value="true"/>
</include>
</group>
<!--Joint effort controllers-->
<group if="$(eval arg('control_type') == 'effort')">
<include file="$(find panda_gazebo)/launch/load_joint_effort_controllers.launch.xml"/>
<include file="$(find panda_gazebo)/launch/load_joint_group_effort_controller.launch.xml"/>
</group>
<!--Joint_trajectory controller-->
<include unless="$(eval arg('control_type') == 'position')" file="$(find panda_gazebo)/launch/load_effort_joint_trajectory_controllers.launch.xml">
<include unless="$(eval arg('control_type') == 'position')" file="$(find panda_gazebo)/launch/load_effort_joint_trajectory_controller.launch.xml">
<arg name="stopped" value="$(eval arg('control_type') == 'effort')"/>
</include>
</launch>
</launch>
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<!-- Launch file for launching the robot controllers -->
<!--Launch file that launches a effort joint trajectory controller-->
<launch>
<arg name="stopped" default="false" doc="Spawn the controllers in stoped mode"/>

Expand All @@ -10,4 +10,4 @@
<arg unless="$(arg stopped)" name="command_args" value=""/>

<node name="effort_joint_trajectory_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="$(arg command_args) panda_arm_controller"/>
</launch>
</launch>
13 changes: 0 additions & 13 deletions panda_gazebo/launch/load_joint_effort_controllers.launch.xml

This file was deleted.

12 changes: 12 additions & 0 deletions panda_gazebo/launch/load_joint_group_effort_controller.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
<!--Launch file that launches a joint group effort controller-->
<launch>
<arg name="stopped" default="false" doc="Spawn the controllers in stoped mode"/>

<!--Load controller parameters-->
<rosparam file="$(find panda_gazebo)/cfg/controllers/joint_group_effort_controller.yaml" command="load"/>

<!--Load the controllers-->
<arg if="$(arg stopped)" name="command_args" value="--stopped"/>
<arg unless="$(arg stopped)" name="command_args" value="" />
<node name="joint_effort_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="$(arg command_args) panda_arm_joint_effort_controller"/>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
<!--Launch file that launches a joint group position controller-->
<launch>
<arg name="stopped" default="false" doc="Spawn the controllers in stoped mode"/>

<!--Load controller parameters-->
<rosparam file="$(find panda_gazebo)/cfg/controllers/joint_group_position_controller.yaml" command="load"/>

<!--Load the controllers-->
<arg if="$(arg stopped)" name="command_args" value="--stopped"/>
<arg unless="$(arg stopped)" name="command_args" value=""/>
<node name="joint_position_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="$(arg command_args) panda_arm_joint_position_controller"/>
</launch>
13 changes: 0 additions & 13 deletions panda_gazebo/launch/load_joint_position_controllers.launch.xml

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<!-- Launch file for launching the robot controllers -->
<!--Launch file that launches a position joint trajectory controller-->
<launch>
<arg name="stopped" default="false"/>

Expand All @@ -9,4 +9,4 @@
<arg if="$(arg stopped)" name="command_args" value="--stopped"/>
<arg unless="$(arg stopped)" name="command_args" value=""/>
<node name="position_joint_trajectory_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="$(arg command_args) panda_arm_controller"/>
</launch>
</launch>
10 changes: 5 additions & 5 deletions panda_gazebo/launch/panda_rviz.launch.xml
Original file line number Diff line number Diff line change
@@ -1,18 +1,18 @@
<!-- Launch file for loading RVIZ -->
<!--Launch file for loading RVIZ -->
<launch>
<!-- GDB Debug Option -->
<!--GDB Debug Option-->
<arg name="debug" default="false" doc="Add gdb debug flag"/>
<arg unless="$(arg debug)" name="launch_prefix" value=""/>
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args"/>
<!-- rviz launch arguments -->
<!--rviz launch arguments-->
<arg name="moveit" default="false" doc="Start MoveIt"/>
<arg unless="$(arg moveit)" name="rviz_file_default" value="$(find panda_gazebo)/launch/includes/rviz/panda.rviz"/>
<arg if="$(arg moveit)" name="rviz_file_default" value="$(find panda_gazebo)/launch/includes/rviz/panda_moveit.rviz"/>
<arg name="rviz_file" default="$(arg rviz_file_default)" doc="Path to the Rviz configuration file"/>
<arg name="command_args" value="-d $(arg rviz_file)" />

<!-- launch rviz -->
<!--launch rviz-->
<node name="$(anon rviz)" launch-prefix="$(arg launch_prefix)" pkg="rviz" type="rviz" respawn="false" args="$(arg command_args)" output="screen">
<rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
</node>
</launch>
</launch>
10 changes: 4 additions & 6 deletions panda_gazebo/launch/put_robot_in_world.launch
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
<arg name="end_effector" default="panda_link8" doc="The end effector link"/>
<arg name="max_velocity_scaling_factor" default="1.0" doc="Factor used when scaling the MoveIt plan velocity"/>
<arg name="max_acceleration_scaling_factor" default="1.0" doc="Factor used when scaling the MoveIt plan acceleration"/>
<!-- Gazebo specific options -->
<!--Gazebo specific options-->
<arg name="world" default="$(find panda_gazebo)/resources/worlds/empty.world" doc="Path to the world file"/>
<arg name="gazebo" default="false" doc="Start Gazebo"/>
<arg name="paused" default="false" doc="Start gazebo paused"/>
Expand All @@ -23,15 +23,13 @@
<arg name="roll" default="0" doc="How much to rotate the base of the robot around its X-axis in [rad]?"/>
<arg name="pitch" default="0" doc="How much to rotate the base of the robot around its Y-axis in [rad]?"/>
<arg name="yaw" default="0" doc="How much to rotate the base of the robot around its Z-axis in [rad]?"/>
<!--Phyics engines: dart|ode-->
<arg name="physics" default="dart" doc="The physics engine used by gazebo"/>
<!--Control arguments-->
<!-- The control type used for controlling the robot (Options: Trajectory, position, effort)-->
<arg name="control_type" default="trajectory" doc="The type of control used for controlling the arm. Options: trajectory, position, effort"/>
<arg name="brute_force_grasping" default="false" doc="Disable the gripper width reached check when grasping."/>

<!--Retrieve the right transmission for the control type-->
<arg if="$(eval arg('control_type') == 'position')" name="transmission" value="position"/>
<arg unless="$(eval arg('control_type') == 'position')" name="transmission" value="effort"/>

<!--Spawn the Panda robot-->
<include file="$(find franka_gazebo)/launch/panda.launch">
<arg name="gazebo" value="$(arg gazebo)"/>
Expand All @@ -40,13 +38,13 @@
<arg name="paused" value="$(arg paused)"/>
<arg name="world" value="$(arg world)"/>
<arg name="use_gripper" default="$(arg load_gripper)"/>
<arg name="transmission" value="$(arg transmission)"/>
<arg name="x" value="$(arg x)"/>
<arg name="y" value="$(arg y)"/>
<arg name="z" value="$(arg z)"/>
<arg name="roll" value="$(arg roll)"/>
<arg name="pitch" value="$(arg pitch)"/>
<arg name="yaw" value="$(arg yaw)" />
<arg name="physics" value="$(arg physics)"/>
</include>

<!--Set panda_gazebo parameters-->
Expand Down
4 changes: 2 additions & 2 deletions panda_gazebo/launch/start_pick_and_place_world.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<!-- Launch file for starting the grasp gazebo environment -->
<!--Launch file for starting the grasp gazebo environment-->
<launch>
<!--Simulation arguments-->
<arg name="world" value="$(find panda_gazebo)/resources/worlds/pick_and_place.world"/>
Expand All @@ -16,4 +16,4 @@
<arg name="gazebo_gui" value="$(arg gazebo_gui)"/>
<arg name="physics" value="$(arg physics)"/>
</include>
</launch>
</launch>
4 changes: 2 additions & 2 deletions panda_gazebo/launch/start_push_world.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<!-- Launch file for starting the push gazebo environment -->
<!--Launch file for starting the push gazebo environment-->
<launch>
<!--Simulation arguments-->
<arg name="world" value="$(find panda_gazebo)/resources/worlds/push.world"/>
Expand All @@ -16,4 +16,4 @@
<arg name="gazebo_gui" value="$(arg gazebo_gui)"/>
<arg name="physics" value="$(arg physics)"/>
</include>
</launch>
</launch>
4 changes: 2 additions & 2 deletions panda_gazebo/launch/start_reach_world.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<!-- Launch file for starting the reach gazebo environment -->
<!--Launch file for starting the reach gazebo environment-->
<launch>
<!--Simulation arguments-->
<arg name="world" value="$(find panda_gazebo)/resources/worlds/reach.world"/>
Expand All @@ -16,4 +16,4 @@
<arg name="gazebo_gui" value="$(arg gazebo_gui)"/>
<arg name="physics" value="$(arg physics)"/>
</include>
</launch>
</launch>
4 changes: 2 additions & 2 deletions panda_gazebo/launch/start_slide_world.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<!-- Launch file for starting the grasp gazebo environment -->
<!--Launch file for starting the grasp gazebo environment-->
<launch>
<!--Simulation arguments-->
<arg name="world" value="$(find panda_gazebo)/resources/worlds/slide.world"/>
Expand All @@ -16,4 +16,4 @@
<arg name="gazebo_gui" value="$(arg gazebo_gui)"/>
<arg name="physics" value="$(arg physics)"/>
</include>
</launch>
</launch>
4 changes: 2 additions & 2 deletions panda_gazebo/launch/start_world.launch.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<!-- Launch file for starting the empty gazebo environment -->
<!--Launch file for starting the empty gazebo environment-->
<launch>
<!--Simulation arguments-->
<arg name="world" default="$(find panda_gazebo)/resources/worlds/empty.world" doc="Path to the world file"/>
Expand All @@ -15,4 +15,4 @@
<arg name="gui" value="$(arg gazebo_gui)"/>
<arg name="physics" value="$(arg physics)"/>
</include>
</launch>
</launch>
Loading

0 comments on commit b466168

Please sign in to comment.