Skip to content

Commit

Permalink
Feat: xarm_planner and gazebo support lite6
Browse files Browse the repository at this point in the history
  • Loading branch information
vimior committed Apr 29, 2022
1 parent b094047 commit f70591a
Show file tree
Hide file tree
Showing 5 changed files with 61 additions and 3 deletions.
52 changes: 52 additions & 0 deletions xarm_gazebo/launch/lite6_beside_table.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
<?xml version="1.0"?>
<launch>
<arg name="run_demo" default="false" doc="If true, perform the demo after launch"/>
<arg name="paused" default="false" doc="Starts gazebo in paused mode" />
<arg name="gui" default="true" doc="Starts gazebo gui" />
<arg name="effort_control" default="false"/>
<arg name="velocity_control" default="false"/>
<arg name="add_gripper" default="false" />
<arg name="add_vacuum_gripper" default="false" />
<arg name="namespace" default="xarm"/>

<arg name="xarm_velocity_control" value="$(eval arg('velocity_control') and not arg('run_demo'))" />

<rosparam file="$(find lite6_moveit_config)/config/lite6_params.yaml" command="load" ns="$(arg namespace)"/>
<rosparam if="$(arg add_gripper)" file="$(find xarm_controller)/config/gripper_gazebo_ros_control.yaml" command="load"/>
<!-- startup simulated world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find xarm_gazebo)/worlds/xarm_example1_table.world"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="gui" value="$(arg gui)"/>
</include>

<!-- send robot urdf to param server, joint limit may be overwritten if use moveit planner -->
<param unless="$(eval arg('add_gripper') or arg('add_vacuum_gripper'))" name="robot_description"
command="$(find xacro)/xacro
--inorder '$(find xarm_description)/urdf/lite6_robot.urdf.xacro'
effort_control:=$(arg effort_control) velocity_control:=$(arg xarm_velocity_control)" />

<param if="$(arg add_gripper)" name="robot_description"
command="$(find xacro)/xacro
--inorder '$(find xarm_description)/urdf/lite6_with_gripper.xacro'
effort_control:=$(arg effort_control) velocity_control:=$(arg xarm_velocity_control)" />

<param if="$(arg add_vacuum_gripper)" name="robot_description"
command="$(find xacro)/xacro
--inorder '$(find xarm_description)/urdf/lite6_with_vacuum_gripper.xacro'
effort_control:=$(arg effort_control) velocity_control:=$(arg xarm_velocity_control)" />

<!-- spawn robot model in gazebo, located on the table -->
<node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model"
respawn="false" output="screen"
args="-urdf -model lite6 -x -0.2 -y -0.5 -z 1.021 -Y 1.571 -param robot_description"/>

<!-- load the corresponding controllers -->
<include file="$(find xarm_controller)/launch/lite6_control.launch">
<arg name="run_demo_traj" value="$(arg run_demo)"/>
<arg name="effort_control" value="$(arg effort_control)"/>
<arg name="velocity_control" value="$(arg xarm_velocity_control)"/>
<arg name="add_gripper" value="$(arg add_gripper)" />
</include>

</launch>
3 changes: 2 additions & 1 deletion xarm_planner/launch/moveit_real_arm_configurations.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,10 @@
<arg name="show_rviz" default="true" />
<arg name="no_gui_plan" default="true" />
<arg name="report_type" default="normal" />
<arg name="robot_type" default="xarm" />
<arg name="ext_ns" default="" />

<include file="$(eval find('xarm' + str(arg('arm_dof')) + arg('end_effector') + '_moveit_config') + '/launch/realMove_exec.launch')">
<include file="$(eval find(str(arg('robot_type')) + str(arg('arm_dof')) + arg('end_effector') + '_moveit_config') + '/launch/realMove_exec.launch')">
<arg name="robot_ip" value="$(arg robot_ip)" />
<!-- load the default move_group planner (not xarm_simple_planner) -->
<arg name="show_rviz" value="$(arg show_rviz)" />
Expand Down
5 changes: 3 additions & 2 deletions xarm_planner/launch/moveit_sim_configurations.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,10 @@
<arg name="arm_dof" />
<arg name="end_effector" default="" />
<arg name="namespace" default="xarm"/>
<arg name="robot_type" default="xarm" />

<rosparam file="$(eval find('xarm' + str(arg('arm_dof')) + arg('end_effector') + '_moveit_config') + '/config/xarm' + str(arg('arm_dof')) + '_params.yaml')" command="load" ns="$(arg namespace)"/>
<include file="$(eval find('xarm' + str(arg('arm_dof')) + arg('end_effector') + '_moveit_config') + '/launch/moveit_rviz_common.launch')">
<rosparam file="$(eval find(str(arg('robot_type')) + str(arg('arm_dof')) + arg('end_effector') + '_moveit_config') + '/config/' + str(arg('robot_type')) + str(arg('arm_dof')) + '_params.yaml')" command="load" ns="$(arg namespace)"/>
<include file="$(eval find(str(arg('robot_type')) + str(arg('arm_dof')) + arg('end_effector') + '_moveit_config') + '/launch/moveit_rviz_common.launch')">
<arg name="jnt_stat_source" value="[/move_group/fake_controller_joint_states]" />
<!-- whether to use fake_execution controller to drive the motion -->
<arg name="fake_execution" value="true" />
Expand Down
2 changes: 2 additions & 0 deletions xarm_planner/launch/xarm_planner_realHW.launch
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<arg name="add_vacuum_gripper" default="false" />
<arg name="report_type" default="normal" />
<arg name="ext_ns" default="" />
<arg name="robot_type" default="xarm"/>

<remap from="move_group/display_planned_path" to="$(arg ext_ns)/move_group/display_planned_path" />
<include file="$(find xarm_planner)/launch/moveit_real_arm_configurations.launch">
Expand All @@ -20,6 +21,7 @@
<arg name="end_effector" value="_vacuum_gripper" if="$(arg add_vacuum_gripper)" />
<arg name="report_type" value="$(arg report_type)" />
<arg name="ext_ns" value="$(arg ext_ns)" />
<arg name="robot_type" value="$(arg robot_type)" />
</include>

<remap from="DOF" to="$(arg ext_ns)/xarm/DOF" />
Expand Down
2 changes: 2 additions & 0 deletions xarm_planner/launch/xarm_planner_rviz_sim.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,14 @@
<arg name="add_gripper" default="false" />
<arg name="add_vacuum_gripper" default="false" />
<arg name="namespace" default="xarm"/>
<arg name="robot_type" default="xarm"/>

<include file="$(find xarm_planner)/launch/moveit_sim_configurations.launch">
<arg name="arm_dof" value="$(arg robot_dof)" />
<arg name="end_effector" value="_gripper" if="$(arg add_gripper)" />
<arg name="end_effector" value="_vacuum_gripper" if="$(arg add_vacuum_gripper)" />
<arg name="namespace" value="$(arg namespace)" />
<arg name="robot_type" value="$(arg robot_type)" />
</include>

<remap from="/DOF" to="/xarm/DOF" />
Expand Down

0 comments on commit f70591a

Please sign in to comment.