Skip to content

Commit

Permalink
优化pro 600 moveit包-修复rviz添加地面后无法运动规划问题,更新URDF模型初始姿态
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Jan 7, 2025
1 parent fbed374 commit eec1555
Show file tree
Hide file tree
Showing 42 changed files with 985 additions and 341 deletions.
183 changes: 183 additions & 0 deletions mycobot_description/urdf/mycobot_pro_600/mycobot_pro_600_moveit.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,183 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="firefighter" >

<xacro:property name="width" value=".2" />


<link name="base">
<visual>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/mycobot_pro_600/base.dae"/>
</geometry>
<origin xyz = "0 0 0 " rpy = " 0 0 0"/>
</visual>
<collision>
<origin xyz = "0 0 0.04 " rpy = " 0 0 1.5708"/>
<geometry>
<cylinder length="0.06" radius="0.038"/>
</geometry>
</collision>
</link>

<link name="link1">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_600/link1.dae"/>
</geometry>
<origin xyz = "0 0 0 " rpy = "0 0 3.1415926"/>
</visual>
<collision>
<origin xyz = "0.0 0.0 -0.02 " rpy = " 0 0 1.5708"/>
<geometry>
<cylinder length="0.05" radius="0.03"/>
</geometry>
</collision>
</link>


<link name="link2">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot_pro_600/link2.dae"/>
</geometry>
<origin xyz = "0 0 -0.080 " rpy = " 3.1415926 0 3.1415926"/>
</visual>
<collision>
<origin xyz = "0.128 0 -0.125 " rpy = " 0 1.5708 0"/>
<geometry>
<cylinder length="0.28" radius="0.024"/>
</geometry>
</collision>
</link>


<link name="link3">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pro_600/link3.dae"/>
</geometry>
<origin xyz = "0 0 -0.0855 " rpy = " 3.1415926 0 3.1415926"/>
</visual>
<collision>
<origin xyz = "0.128 0.0 -0.003 " rpy = "0 1.5708 0"/>
<geometry>
<cylinder length="0.24" radius="0.024"/>
</geometry>
</collision>
</link>



<link name="link4">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pro_600/link4.dae"/>
</geometry>
<origin xyz = "0 0 0 " rpy = " 0 3.1415926 0"/>
</visual>
<collision>
<origin xyz = "0.0 -0.01 0.007" rpy = " 1.5708 1.5708 0"/>
<geometry>
<cylinder length="0.05" radius="0.024"/>
</geometry>
</collision>
</link>


<link name="link5">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pro_600/link5.dae"/>
</geometry>
<origin xyz = "0 0 0 " rpy = " 0 0 1.5707"/>
</visual>
<collision>
<origin xyz = "0.0 0.0 -0.015 " rpy = " 0 0 -1.5708"/>
<geometry>
<cylinder length="0.05" radius="0.028"/>
</geometry>
</collision>
</link>

<link name="link6">
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot_pro_600/link6.dae"/>
</geometry>
<material name = "grey">
<color rgba = "0.5 0.5 0.5 1"/>
</material>
<origin xyz = "0.03 0 0" rpy = " 0 -1.5707 0"/>
</visual>
<collision>
<origin xyz = "0.006 0.0 -0.0 " rpy = " 0 1.5708 0"/>
<geometry>
<cylinder length="0.006" radius="0.026"/>
</geometry>
</collision>
</link>


<joint name="joint2_to_joint1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
<parent link="base"/>
<child link="link1"/>
<origin xyz= "0 0 0.19934" rpy = "0 0 0"/>
</joint>


<joint name="joint3_to_joint2" type="revolute">
<axis xyz="0 0 -1"/>
<!-- <limit effort = "1000.0" lower = "-4.71" upper = "1.5708" velocity = "0"/> -->
<limit effort = "1000.0" lower = "-3.14159" upper = "3.14159" velocity = "0"/>
<parent link="link1"/>
<child link="link2"/>
<origin xyz= "0 0 0" rpy = "1.5708 -1.5708 0"/>
<!-- <origin xyz= "0 0 0" rpy = "1.5708 0 0"/> -->
</joint>


<joint name="joint4_to_joint3" type="revolute">
<axis xyz=" 0 0 -1"/>
<limit effort = "1000.0" lower = "-2.61" upper = "2.618" velocity = "0"/>
<parent link="link2"/>
<child link="link3"/>
<origin xyz= "0.25 0 0 " rpy = "0 0 0"/>
</joint>

<joint name="joint5_to_joint4" type="revolute">
<axis xyz=" 0 0 -1"/>
<!-- <limit effort = "1000.0" lower = "-4.53" upper = "1.3962" velocity = "0"/> -->
<limit effort = "1000.0" lower = "-2.9670" upper = "2.9670" velocity = "0"/>
<parent link="link3"/>
<child link="link4"/>
<origin xyz= "0.25 0 -0.1091" rpy = "0 0 1.5708"/>
<!-- <origin xyz= "0.25 0 -0.1091" rpy = "0 0 0"/> -->
</joint>

<joint name="joint6_to_joint5" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-2.93" upper = "2.9321" velocity = "0"/>
<parent link="link4"/>
<child link="link5"/>
<origin xyz= "0 -0.108 0" rpy = "1.57080 -1.57080 0"/>
</joint>

<joint name="joint6output_to_joint6" type="revolute">
<axis xyz="-1 0 0"/>
<limit effort = "1000.0" lower = "-3.03" upper = "3.0368" velocity = "0"/>
<parent link="link5"/>
<child link="link6"/>
<origin xyz= "-0.07586 0 0" rpy = "-1.57080 0 0 "/>
</joint>



</robot>

4 changes: 2 additions & 2 deletions mycobot_pro/mycobot_600_moveit/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
moveit_setup_assistant_config:
URDF:
package: mycobot_description
relative_path: urdf/mycobot_pro_600/mycobot_pro_600.urdf
relative_path: urdf/mycobot_pro_600/mycobot_pro_600_moveit.urdf
xacro_args: "--inorder "
SRDF:
relative_path: config/firefighter.srdf
CONFIG:
author_name: wangweijian
author_email: [email protected]
generated_timestamp: 1652406964
generated_timestamp: 1736245598
15 changes: 2 additions & 13 deletions mycobot_pro/mycobot_600_moveit/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,21 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.1.3)
project(mycobot_600_moveit)

find_package(catkin REQUIRED
rospy
std_msgs
moveit_msgs
)
find_package(catkin REQUIRED)

catkin_package()

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
catkin_install_python(PROGRAMS
scripts/sync_plan.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
PATTERN "setup_assistant.launch" EXCLUDE)
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
5 changes: 5 additions & 0 deletions mycobot_pro/mycobot_600_moveit/config/cartesian_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
cartesian_limits:
max_trans_vel: 1
max_trans_acc: 2.25
max_trans_dec: -5
max_rot_vel: 1.57
8 changes: 4 additions & 4 deletions mycobot_pro/mycobot_600_moveit/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,12 @@ learning_rate: 0.01
smoothness_cost_velocity: 0.0
smoothness_cost_acceleration: 1.0
smoothness_cost_jerk: 0.0
ridge_factor: 0.01
ridge_factor: 0.0
use_pseudo_inverse: false
pseudo_inverse_ridge_factor: 1e-4
joint_update_limit: 0.1
collision_clearence: 0.2
collision_clearance: 0.2
collision_threshold: 0.07
use_stochastic_descent: true
enable_failure_recovery: true
max_recovery_attempts: 5
enable_failure_recovery: false
max_recovery_attempts: 5
6 changes: 5 additions & 1 deletion mycobot_pro/mycobot_600_moveit/config/fake_controllers.yaml
Original file line number Diff line number Diff line change
@@ -1,9 +1,13 @@
controller_list:
- name: fake_arm_group_controller
type: $(arg fake_execution_type)
joints:
- joint2_to_joint1
- joint3_to_joint2
- joint4_to_joint3
- joint5_to_joint4
- joint6_to_joint5
- joint6output_to_joint6
- joint6output_to_joint6
initial: # Define initial robot poses per group
- group: arm_group
pose: init_pose
69 changes: 31 additions & 38 deletions mycobot_pro/mycobot_600_moveit/config/firefighter.srdf
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<?xml version="1.0" ?>
<?xml version="1.0" encoding="UTF-8"?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
Expand All @@ -10,47 +10,40 @@
<!--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="arm_group">
<joint name="joint2_to_joint1" />
<joint name="joint3_to_joint2" />
<joint name="joint4_to_joint3" />
<joint name="joint5_to_joint4" />
<joint name="joint6_to_joint5" />
<joint name="joint6output_to_joint6" />
<joint name="joint2_to_joint1"/>
<joint name="joint3_to_joint2"/>
<joint name="joint4_to_joint3"/>
<joint name="joint5_to_joint4"/>
<joint name="joint6_to_joint5"/>
<joint name="joint6output_to_joint6"/>
</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="init_pose" group="arm_group">
<joint name="joint2_to_joint1" value="0" />
<joint name="joint3_to_joint2" value="-1.5708" />
<joint name="joint4_to_joint3" value="0" />
<joint name="joint5_to_joint4" value="-1.5708" />
<joint name="joint6_to_joint5" value="0" />
<joint name="joint6output_to_joint6" value="0" />
<joint name="joint2_to_joint1" value="0"/>
<joint name="joint3_to_joint2" value="0"/>
<joint name="joint4_to_joint3" value="0"/>
<joint name="joint5_to_joint4" value="0"/>
<joint name="joint6_to_joint5" value="0"/>
<joint name="joint6output_to_joint6" value="0"/>
</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="vitual_joint" type="fixed" parent_frame="basic" child_link="joint1" /> -->
<virtual_joint name="vitual_joint" type="fixed" parent_frame="basic" child_link="base" />

<virtual_joint name="vitual_joint" type="fixed" parent_frame="basic" child_link="base"/>
<!--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="base" link2="link1" reason="Adjacent" />
<disable_collisions link1="base" link2="link2" reason="Never" />
<disable_collisions link1="base" link2="link3" reason="Never" />
<disable_collisions link1="base" link2="link4" reason="Never" />
<disable_collisions link1="base" link2="link5" reason="Never" />
<disable_collisions link1="base" link2="link6" reason="Never" />
<disable_collisions link1="link1" link2="link2" reason="Adjacent" />
<disable_collisions link1="link1" link2="link3" reason="Never" />
<disable_collisions link1="link1" link2="link4" reason="Never" />
<disable_collisions link1="link1" link2="link5" reason="Never" />
<disable_collisions link1="link1" link2="link6" reason="Never" />
<disable_collisions link1="link2" link2="link3" reason="Adjacent" />
<disable_collisions link1="link2" link2="link4" reason="Never" />
<disable_collisions link1="link2" link2="link5" reason="Never" />
<disable_collisions link1="link2" link2="link6" reason="Never" />
<disable_collisions link1="link3" link2="link4" reason="Adjacent" />
<disable_collisions link1="link3" link2="link5" reason="Never" />
<disable_collisions link1="link3" link2="link6" reason="Never" />
<disable_collisions link1="link4" link2="link5" reason="Adjacent" />
<disable_collisions link1="link4" link2="link6" reason="Never" />
<disable_collisions link1="link5" link2="link6" reason="Adjacent" />
<disable_collisions link1="base" link2="link1" reason="Adjacent"/>
<disable_collisions link1="base" link2="link2" reason="Never"/>
<disable_collisions link1="base" link2="link4" reason="Never"/>
<disable_collisions link1="base" link2="link5" reason="Never"/>
<disable_collisions link1="link1" link2="link2" reason="Adjacent"/>
<disable_collisions link1="link1" link2="link3" reason="Never"/>
<disable_collisions link1="link1" link2="link4" reason="Never"/>
<disable_collisions link1="link1" link2="link5" reason="Never"/>
<disable_collisions link1="link1" link2="link6" reason="Never"/>
<disable_collisions link1="link2" link2="link3" reason="Adjacent"/>
<disable_collisions link1="link2" link2="link4" reason="Never"/>
<disable_collisions link1="link3" link2="link4" reason="Adjacent"/>
<disable_collisions link1="link3" link2="link5" reason="Never"/>
<disable_collisions link1="link3" link2="link6" reason="Never"/>
<disable_collisions link1="link4" link2="link5" reason="Adjacent"/>
<disable_collisions link1="link4" link2="link6" reason="Never"/>
<disable_collisions link1="link5" link2="link6" reason="Adjacent"/>
</robot>
4 changes: 4 additions & 0 deletions mycobot_pro/mycobot_600_moveit/config/gazebo_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Publish joint_states
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
Loading

0 comments on commit eec1555

Please sign in to comment.