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

Integrate with Gazebo #68

Closed
wants to merge 3 commits into from
Closed
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
125 changes: 64 additions & 61 deletions config/panda_arm.xacro
Original file line number Diff line number Diff line change
@@ -1,64 +1,67 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:macro name="panda_arm">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="panda_arm">
<chain base_link="panda_link0" tip_link="panda_link8" />
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="ready" group="panda_arm">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.785" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="-2.356" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="1.571" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<group_state name="extended" group="panda_arm">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="0" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="0" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="0" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<group_state name="transport" group="panda_arm">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.5599" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="-2.97" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="0" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="floating" parent_frame="world" child_link="panda_link0" />
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent" />
<disable_collisions link1="panda_link0" link2="panda_link2" reason="Never" />
<disable_collisions link1="panda_link0" link2="panda_link3" reason="Never" />
<disable_collisions link1="panda_link0" link2="panda_link4" reason="Never" />
<disable_collisions link1="panda_link1" link2="panda_link2" reason="Adjacent" />
<disable_collisions link1="panda_link1" link2="panda_link3" reason="Default" />
<disable_collisions link1="panda_link1" link2="panda_link4" reason="Never" />
<disable_collisions link1="panda_link2" link2="panda_link3" reason="Adjacent" />
<disable_collisions link1="panda_link2" link2="panda_link4" reason="Never" />
<disable_collisions link1="panda_link3" link2="panda_link4" reason="Adjacent" />
<disable_collisions link1="panda_link3" link2="panda_link6" reason="Never" />
<disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent" />
<disable_collisions link1="panda_link4" link2="panda_link6" reason="Never" />
<disable_collisions link1="panda_link4" link2="panda_link7" reason="Never" />
<disable_collisions link1="panda_link4" link2="panda_link8" reason="Never" />
<disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent" />
<disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent" />
<disable_collisions link1="panda_link6" link2="panda_link8" reason="Default" />
<disable_collisions link1="panda_link7" link2="panda_link8" reason="Adjacent" />
</xacro:macro>
<xacro:macro name="panda_arm">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="panda_arm">
<joint name="panda_joint1"/>
<joint name="panda_joint2"/>
<joint name="panda_joint3"/>
<joint name="panda_joint4"/>
<joint name="panda_joint5"/>
<joint name="panda_joint6"/>
<joint name="panda_joint7"/>
<joint name="panda_joint8"/>
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="ready" group="panda_arm">
<joint name="panda_joint1" value="0"/>
<joint name="panda_joint2" value="-0.785"/>
<joint name="panda_joint3" value="0"/>
<joint name="panda_joint4" value="-2.356"/>
<joint name="panda_joint5" value="0"/>
<joint name="panda_joint6" value="1.571"/>
<joint name="panda_joint7" value="-0.7855"/>
</group_state>
<group_state name="extended" group="panda_arm">
<joint name="panda_joint1" value="0"/>
<joint name="panda_joint2" value="-0.3927"/>
<joint name="panda_joint3" value="0"/>
<joint name="panda_joint4" value="-0.7855"/>
<joint name="panda_joint5" value="0"/>
<joint name="panda_joint6" value="3.142"/>
<joint name="panda_joint7" value="-0.785"/>
</group_state>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="panda_link0"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent"/>
<disable_collisions link1="panda_link0" link2="panda_link2" reason="Never"/>
<disable_collisions link1="panda_link0" link2="panda_link3" reason="Never"/>
<disable_collisions link1="panda_link0" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link1" link2="panda_link2" reason="Adjacent"/>
<disable_collisions link1="panda_link1" link2="panda_link3" reason="Default"/>
<disable_collisions link1="panda_link1" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link2" link2="panda_link3" reason="Adjacent"/>
<disable_collisions link1="panda_link2" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link3" link2="panda_link4" reason="Adjacent"/>
<disable_collisions link1="panda_link3" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent"/>
<disable_collisions link1="panda_link4" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_link7" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_link8" reason="Never"/>
<disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent"/>
<disable_collisions link1="panda_link5" link2="panda_link7" reason="Default"/>
<disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent"/>
<disable_collisions link1="panda_link7" link2="panda_link8" reason="Adjacent"/>
<!-- Fix self-collisions between too coarse collision geometries provided by franka_description
See https://github.com/ros-planning/panda_moveit_config/issues/72#issuecomment-768472329
https://github.com/ros-planning/panda_moveit_config/pull/35#pullrequestreview-390715967
-->
<disable_collisions link1="panda_link5" link2="panda_link8" reason="Default" />
<disable_collisions link1="panda_link6" link2="panda_link8" reason="Default"/>
</xacro:macro>
</robot>
20 changes: 20 additions & 0 deletions config/ros_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# Simulation settings for using moveit_sim_controllers
moveit_sim_hw_interface:
joint_model_group: panda_arm
joint_model_group_pose: ready
# Settings for ros_control_boilerplate control loop
generic_hw_control_loop:
loop_hz: 300
cycle_time_error_threshold: 0.01
# Settings for ros_control hardware interface
hardware_interface:
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
- panda_finger_joint1
sim_control_mode: 1 # 0: position, 1: velocity
51 changes: 51 additions & 0 deletions launch/demo_gazebo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
<launch>

<!-- By default, we do not start a database (it can be large) -->
<arg name="db" default="false" />
<!-- Allow user to specify database location -->
<arg name="db_path" default="$(find panda_moveit_config)/default_warehouse_mongo_db" />

<!-- By default, we are not in debug mode -->
<arg name="debug" default="false" />

<!-- By default, we won't load or override the robot_description -->
<arg name="load_robot_description" default="false"/>
<arg name="load_gripper" default="true" />

<!-- Gazebo specific options -->
<arg name="gazebo_gui" default="true"/>
<arg name="paused" default="false"/>

<!-- launch the gazebo simulator and spawn the robot -->
<include file="$(find franka_gazebo)/launch/panda.launch">
<arg unless="$(arg gazebo_gui)" name="headless" value="true"/>
<arg if="$(arg gazebo_gui)" name="headless" value="false"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_gripper" default="$(arg load_gripper)"/>
<arg name="transmission" value="hardware_interface/PositionJointInterface"/>
<arg name="controller" value="position_joint_trajectory_controller"/>
</include>

<!-- Load position_joint_trajectory_controller -->
<include file="$(find panda_moveit_config)/launch/ros_controllers.launch"/>

<!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
<include ns="panda" file="$(find panda_moveit_config)/launch/move_group.launch">
<arg name="info" value="true"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="allow_trajectory_execution" value="true"/>
<arg name="fake_execution" value="false"/>
<arg name="load_gripper" value="$(arg load_gripper)"/>
</include>

<!-- Run Rviz and load the default config to see the state of the move_group node -->
<include ns="panda" file="$(dirname)/moveit_rviz.launch">
<arg name="debug" value="$(arg debug)"/>
</include>

<!-- If database loading was enabled, start mongodb as well -->
<include file="$(dirname)/default_warehouse_db.launch" if="$(arg db)">
<arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
</include>

</launch>
2 changes: 1 addition & 1 deletion launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param name="$(arg robot_description)" command="$(find xacro)/xacro $(find franka_description)/robots/panda_arm.urdf.xacro hand:=$(arg load_gripper)" />
<param name="$(arg robot_description)" command="$(find xacro)/xacro $(find franka_description)/robots/panda_arm.urdf.xacro hand:=$(arg load_gripper)" if="$(arg load_robot_description)"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro '$(find panda_moveit_config)/config/panda_arm_hand.srdf.xacro'" if="$(arg load_gripper)" />
Expand Down
10 changes: 10 additions & 0 deletions launch/ros_controllers.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<?xml version="1.0"?>
<launch>

<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find panda_moveit_config)/config/ros_controllers.yaml" command="load"/>

<!-- Load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="position_joint_trajectory_controller"/>

</launch>
10 changes: 7 additions & 3 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,12 @@
<run_depend>joint_state_publisher_gui</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>xacro</run_depend>
<run_depend>topic_tools</run_depend>
<!-- This package is referenced in the warehouse launch files, but does not build out of the box at the moment.
Commented the dependency until this works. -->
<run_depend>moveit_visual_tools</run_depend>
<!-- The next 2 packages are required for the gazebo simulation.
We don't include them by default to prevent installing gazebo and all its dependencies. -->
<!-- <run_depend>joint_trajectory_controller</run_depend> -->
<!-- <run_depend>gazebo_ros_control</run_depend> -->
<!-- <run_depend>franka_gazebo</run_depend> -->
<!-- This package is referenced in the warehouse launch files, but does not build out of the box at the moment. Commented the dependency until this works. -->
<!-- <run_depend>warehouse_ros_mongo</run_depend> -->
</package>