Skip to content

Commit fbd15bc

Browse files
committed
优化630 moveit包-修复rviz添加地面后无法运动规划问题,更新URDF模型初始姿态
1 parent 7e8e360 commit fbd15bc

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

43 files changed

+981
-322
lines changed
Lines changed: 175 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,175 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="firefighter" >
3+
4+
<xacro:property name="width" value=".2" />
5+
6+
7+
<link name="base">
8+
<visual>
9+
<geometry>
10+
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/base.dae"/>
11+
</geometry>
12+
<origin xyz = "0 0 0 " rpy = " 1.5707 0 0"/>
13+
</visual>
14+
<collision>
15+
<origin xyz = "0 0 0.04 " rpy = " 0 0 1.5708"/>
16+
<geometry>
17+
<cylinder length="0.08" radius="0.06"/>
18+
</geometry>
19+
</collision>
20+
</link>
21+
22+
<link name="link1">
23+
<visual>
24+
<geometry>
25+
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link1.dae"/>
26+
</geometry>
27+
<origin xyz = "0 0 -0.06 " rpy = "0 0 3.1415926"/>
28+
</visual>
29+
<collision>
30+
<origin xyz = "0.0 0.0 -0.02 " rpy = " 0 0 1.5708"/>
31+
<geometry>
32+
<cylinder length="0.06" radius="0.03"/>
33+
</geometry>
34+
</collision>
35+
</link>
36+
37+
38+
<link name="link2">
39+
<visual>
40+
<geometry>
41+
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link2.dae"/>
42+
</geometry>
43+
<origin xyz = "0 0 -0.0446 " rpy = " 0 -1.5707 -1.5707"/>
44+
</visual>
45+
<collision>
46+
<origin xyz = "0.14 0 -0.08 " rpy = " 0 1.5708 0"/>
47+
<geometry>
48+
<cylinder length="0.28" radius="0.028"/>
49+
</geometry>
50+
</collision>
51+
</link>
52+
53+
54+
<link name="link3">
55+
<visual>
56+
<geometry>
57+
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link3.dae"/>
58+
</geometry>
59+
<origin xyz = "0 0 -0.0444 " rpy = " 0 1.5707 -1.5707"/>
60+
</visual>
61+
<collision>
62+
<origin xyz = "0.13 0.0 0.02 " rpy = "0 1.5708 0"/>
63+
<geometry>
64+
<cylinder length="0.28" radius="0.024"/>
65+
</geometry>
66+
</collision>
67+
</link>
68+
69+
70+
<link name="link4">
71+
<visual>
72+
<geometry>
73+
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link4.dae"/>
74+
</geometry>
75+
<origin xyz = "0 0 0.041 " rpy = " -1.5707 0 1.5707"/>
76+
</visual>
77+
<collision>
78+
<origin xyz = "0.0 -0.01 0.007" rpy = " 1.5708 1.5708 0"/>
79+
<geometry>
80+
<cylinder length="0.05" radius="0.024"/>
81+
</geometry>
82+
</collision>
83+
</link>
84+
85+
86+
<link name="link5">
87+
<visual>
88+
<geometry>
89+
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link5.dae"/>
90+
</geometry>
91+
<origin xyz = "-0.043 0 0 " rpy = " 0 -1.5707 3.1415926"/>
92+
</visual>
93+
<collision>
94+
<origin xyz = "0.0 0.0 -0.015 " rpy = " 0 0 -1.5708"/>
95+
<geometry>
96+
<cylinder length="0.05" radius="0.028"/>
97+
</geometry>
98+
</collision>
99+
</link>
100+
101+
<link name="link6">
102+
<visual>
103+
<geometry>
104+
<mesh filename="package://mycobot_description/urdf/mycobot_pro_630/link6.dae"/>
105+
</geometry>
106+
<!-- <material name = "grey">
107+
<color rgba = "0.5 0.5 0.5 1"/>
108+
</material> -->
109+
<origin xyz = "0.01 0 0" rpy = " 0 1.5707 0"/>
110+
</visual>
111+
<collision>
112+
<origin xyz = "0.006 0.0 -0.0 " rpy = " 0 1.5708 0"/>
113+
<geometry>
114+
<cylinder length="0.006" radius="0.026"/>
115+
</geometry>
116+
</collision>
117+
</link>
118+
119+
120+
<joint name="joint1_to_base" type="revolute">
121+
<axis xyz="0 0 1"/>
122+
<limit effort = "1000.0" lower = "-3.14" upper = "3.14159" velocity = "0"/>
123+
<parent link="base"/>
124+
<child link="link1"/>
125+
<origin xyz= "0 0 0.22934" rpy = "0 0 0"/>
126+
</joint>
127+
128+
129+
<joint name="joint2_to_joint1" type="revolute">
130+
<axis xyz="0 0 -1"/>
131+
<!-- <limit effort = "1000.0" lower = "-4.71" upper = "1.5707" velocity = "0"/> -->
132+
<limit effort = "1000.0" lower = "-3.14159" upper = "3.14159" velocity = "0"/>
133+
<parent link="link1"/>
134+
<child link="link2"/>
135+
<origin xyz= "0 0 0" rpy = "1.5707 -1.5708 0"/>
136+
</joint>
137+
138+
139+
<joint name="joint3_to_joint2" type="revolute">
140+
<axis xyz=" 0 0 -1"/>
141+
<limit effort = "1000.0" lower = "-2.61" upper = "2.618" velocity = "0"/>
142+
<parent link="link2"/>
143+
<child link="link3"/>
144+
<origin xyz= "0.27 0 0 " rpy = "0 0 0"/>
145+
</joint>
146+
147+
<joint name="joint4_to_joint3" type="revolute">
148+
<axis xyz=" 0 0 -1"/>
149+
<!-- <limit effort = "1000.0" lower = "-4.53" upper = "1.3962" velocity = "0"/> -->
150+
<limit effort = "1000.0" lower = "-2.9670" upper = "2.9670" velocity = "0"/>
151+
<parent link="link3"/>
152+
<child link="link4"/>
153+
<origin xyz= "0.267 0 -0.0745" rpy = "0 0 1.5708"/>
154+
</joint>
155+
156+
<joint name="joint5_to_joint4" type="revolute">
157+
<axis xyz="0 0 1"/>
158+
<limit effort = "1000.0" lower = "-2.93" upper = "2.9321" velocity = "0"/>
159+
<parent link="link4"/>
160+
<child link="link5"/>
161+
<origin xyz= "0 -0.095 0.002" rpy = "1.5707 -1.5707 0"/>
162+
</joint>
163+
164+
<joint name="joint6_to_joint5" type="revolute">
165+
<axis xyz="-1 0 0"/>
166+
<limit effort = "1000.0" lower = "-3.03" upper = "3.0368" velocity = "0"/>
167+
<parent link="link5"/>
168+
<child link="link6"/>
169+
<origin xyz= "-0.054 0 0" rpy = "-1.5707 0 0 "/>
170+
</joint>
171+
172+
173+
174+
</robot>
175+
Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
11
moveit_setup_assistant_config:
22
URDF:
33
package: mycobot_description
4-
relative_path: urdf/mycobot_pro_630/mycobot_pro_630.urdf
4+
relative_path: urdf/mycobot_pro_630/mycobot_pro_630_moveit.urdf
55
xacro_args: "--inorder "
66
SRDF:
77
relative_path: config/firefighter.srdf
88
CONFIG:
99
author_name: wangweijian
1010
author_email: weijian.wang@elephantrobotics.com
11-
generated_timestamp: 1652406964
11+
generated_timestamp: 1736239899
Lines changed: 2 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1,21 +1,10 @@
1-
cmake_minimum_required(VERSION 2.8.3)
1+
cmake_minimum_required(VERSION 3.1.3)
22
project(mycobot_630_moveit)
33

4-
find_package(catkin REQUIRED
5-
rospy
6-
std_msgs
7-
moveit_msgs
8-
)
4+
find_package(catkin REQUIRED)
95

106
catkin_package()
117

12-
## Mark executable scripts (Python etc.) for installation
13-
## in contrast to setup.py, you can choose the destination
14-
catkin_install_python(PROGRAMS
15-
scripts/sync_plan.py
16-
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
17-
)
18-
198
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
209
PATTERN "setup_assistant.launch" EXCLUDE)
2110
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
cartesian_limits:
2+
max_trans_vel: 1
3+
max_trans_acc: 2.25
4+
max_trans_dec: -5
5+
max_rot_vel: 1.57

mycobot_pro/mycobot_630_moveit/config/chomp_planning.yaml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -7,12 +7,12 @@ learning_rate: 0.01
77
smoothness_cost_velocity: 0.0
88
smoothness_cost_acceleration: 1.0
99
smoothness_cost_jerk: 0.0
10-
ridge_factor: 0.01
10+
ridge_factor: 0.0
1111
use_pseudo_inverse: false
1212
pseudo_inverse_ridge_factor: 1e-4
1313
joint_update_limit: 0.1
14-
collision_clearence: 0.2
14+
collision_clearance: 0.2
1515
collision_threshold: 0.07
1616
use_stochastic_descent: true
17-
enable_failure_recovery: true
18-
max_recovery_attempts: 5
17+
enable_failure_recovery: false
18+
max_recovery_attempts: 5
Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,13 @@
11
controller_list:
22
- name: fake_arm_group_controller
3+
type: $(arg fake_execution_type)
34
joints:
45
- joint1_to_base
56
- joint2_to_joint1
67
- joint3_to_joint2
78
- joint4_to_joint3
89
- joint5_to_joint4
9-
- joint6_to_joint5
10+
- joint6_to_joint5
11+
initial: # Define initial robot poses per group
12+
- group: arm_group
13+
pose: init_pose
Lines changed: 27 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
<?xml version="1.0" ?>
1+
<?xml version="1.0" encoding="UTF-8"?>
22
<!--This does not replace URDF, and is not an extension of URDF.
33
This is a format for representing semantic information about the robot structure.
44
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
@@ -10,47 +10,36 @@
1010
<!--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-->
1111
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
1212
<group name="arm_group">
13-
<joint name="joint1_to_base" />
14-
<joint name="joint2_to_joint1" />
15-
<joint name="joint3_to_joint2" />
16-
<joint name="joint4_to_joint3" />
17-
<joint name="joint5_to_joint4" />
18-
<joint name="joint6_to_joint5" />
13+
<joint name="joint1_to_base"/>
14+
<joint name="joint2_to_joint1"/>
15+
<joint name="joint3_to_joint2"/>
16+
<joint name="joint4_to_joint3"/>
17+
<joint name="joint5_to_joint4"/>
18+
<joint name="joint6_to_joint5"/>
1919
</group>
2020
<!--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'-->
2121
<group_state name="init_pose" group="arm_group">
22-
<joint name="joint1_to_base" value="0" />
23-
<joint name="joint2_to_joint1" value="-1.5708" />
24-
<joint name="joint3_to_joint2" value="0" />
25-
<joint name="joint4_to_joint3" value="-1.5708" />
26-
<joint name="joint5_to_joint4" value="0" />
27-
<joint name="joint6_to_joint5" value="0" />
22+
<joint name="joint1_to_base" value="0"/>
23+
<joint name="joint2_to_joint1" value="0"/>
24+
<joint name="joint3_to_joint2" value="0"/>
25+
<joint name="joint4_to_joint3" value="0"/>
26+
<joint name="joint5_to_joint4" value="0"/>
27+
<joint name="joint6_to_joint5" value="0"/>
2828
</group_state>
2929
<!--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)-->
30-
31-
<!-- <virtual_joint name="vitual_joint" type="fixed" parent_frame="basic" child_link="joint1" /> -->
32-
<virtual_joint name="vitual_joint" type="fixed" parent_frame="basic" child_link="base" />
33-
30+
<virtual_joint name="vitual_joint" type="fixed" parent_frame="basic" child_link="base"/>
3431
<!--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. -->
35-
<disable_collisions link1="base" link2="link1" reason="Adjacent" />
36-
<disable_collisions link1="base" link2="link2" reason="Never" />
37-
<disable_collisions link1="base" link2="link3" reason="Never" />
38-
<disable_collisions link1="base" link2="link4" reason="Never" />
39-
<disable_collisions link1="base" link2="link5" reason="Never" />
40-
<disable_collisions link1="base" link2="link6" reason="Never" />
41-
<disable_collisions link1="link1" link2="link2" reason="Adjacent" />
42-
<disable_collisions link1="link1" link2="link3" reason="Never" />
43-
<disable_collisions link1="link1" link2="link4" reason="Never" />
44-
<disable_collisions link1="link1" link2="link5" reason="Never" />
45-
<disable_collisions link1="link1" link2="link6" reason="Never" />
46-
<disable_collisions link1="link2" link2="link3" reason="Adjacent" />
47-
<disable_collisions link1="link2" link2="link4" reason="Never" />
48-
<disable_collisions link1="link2" link2="link5" reason="Never" />
49-
<disable_collisions link1="link2" link2="link6" reason="Never" />
50-
<disable_collisions link1="link3" link2="link4" reason="Adjacent" />
51-
<disable_collisions link1="link3" link2="link5" reason="Never" />
52-
<disable_collisions link1="link3" link2="link6" reason="Never" />
53-
<disable_collisions link1="link4" link2="link5" reason="Adjacent" />
54-
<disable_collisions link1="link4" link2="link6" reason="Never" />
55-
<disable_collisions link1="link5" link2="link6" reason="Adjacent" />
32+
<disable_collisions link1="base" link2="link1" reason="Adjacent"/>
33+
<disable_collisions link1="link1" link2="link2" reason="Adjacent"/>
34+
<disable_collisions link1="link1" link2="link3" reason="Never"/>
35+
<disable_collisions link1="link1" link2="link4" reason="Never"/>
36+
<disable_collisions link1="link1" link2="link5" reason="Never"/>
37+
<disable_collisions link1="link2" link2="link3" reason="Adjacent"/>
38+
<disable_collisions link1="link2" link2="link4" reason="Never"/>
39+
<disable_collisions link1="link3" link2="link4" reason="Adjacent"/>
40+
<disable_collisions link1="link3" link2="link5" reason="Never"/>
41+
<disable_collisions link1="link3" link2="link6" reason="Never"/>
42+
<disable_collisions link1="link4" link2="link5" reason="Adjacent"/>
43+
<disable_collisions link1="link4" link2="link6" reason="Never"/>
44+
<disable_collisions link1="link5" link2="link6" reason="Adjacent"/>
5645
</robot>
Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
# Publish joint_states
2+
joint_state_controller:
3+
type: joint_state_controller/JointStateController
4+
publish_rate: 50

0 commit comments

Comments
 (0)