-
Notifications
You must be signed in to change notification settings - Fork 85
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
优化pro 600 moveit包-修复rviz添加地面后无法运动规划问题,更新URDF模型初始姿态
- Loading branch information
Showing
42 changed files
with
985 additions
and
341 deletions.
There are no files selected for viewing
183 changes: 183 additions & 0 deletions
183
mycobot_description/urdf/mycobot_pro_600/mycobot_pro_600_moveit.urdf
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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> | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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}) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
4 changes: 4 additions & 0 deletions
4
mycobot_pro/mycobot_600_moveit/config/gazebo_controllers.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
Oops, something went wrong.