Skip to content

Commit

Permalink
更新280JN moveit
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Sep 12, 2024
1 parent f443406 commit 70e59b5
Show file tree
Hide file tree
Showing 41 changed files with 810 additions and 447 deletions.
2 changes: 1 addition & 1 deletion mycobot_280/mycobot_280jn_moveit/.setup_assistant
Original file line number Diff line number Diff line change
Expand Up @@ -8,4 +8,4 @@ moveit_setup_assistant_config:
CONFIG:
author_name: zachary
author_email: [email protected]
generated_timestamp: 1626074107
generated_timestamp: 1726131211
16 changes: 2 additions & 14 deletions mycobot_280/mycobot_280jn_moveit/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,22 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.1.3)
project(mycobot_280jn_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
scripts/path_planning_and_obstacle_avoidance_demo.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_280/mycobot_280jn_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_280/mycobot_280jn_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
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
60 changes: 36 additions & 24 deletions mycobot_280/mycobot_280jn_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,33 +10,45 @@
<!--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="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" />
<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="g_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="joint1" link2="joint2" reason="Adjacent" />
<disable_collisions link1="joint1" link2="joint5" reason="Never" />
<disable_collisions link1="joint2" link2="joint3" reason="Adjacent" />
<disable_collisions link1="joint2" link2="joint5" reason="Never" />
<disable_collisions link1="joint3" link2="joint4" reason="Adjacent" />
<disable_collisions link1="joint3" link2="joint5" reason="Never" />
<disable_collisions link1="joint4" link2="joint5" reason="Adjacent" />
<disable_collisions link1="joint5" link2="joint6" reason="Adjacent" />
<disable_collisions link1="joint5" link2="joint6_flange" reason="Never" />
<disable_collisions link1="joint6" link2="joint6_flange" reason="Adjacent" />
<disable_collisions link1="g_base" link2="joint1" reason="Adjacent"/>
<disable_collisions link1="g_base" link2="joint2" reason="Never"/>
<disable_collisions link1="g_base" link2="joint3" reason="Never"/>
<disable_collisions link1="g_base" link2="joint4" reason="Never"/>
<disable_collisions link1="g_base" link2="joint5" reason="Default"/>
<disable_collisions link1="g_base" link2="joint6" reason="Never"/>
<disable_collisions link1="g_base" link2="joint6_flange" reason="Never"/>
<disable_collisions link1="joint1" link2="joint2" reason="Adjacent"/>
<disable_collisions link1="joint1" link2="joint3" reason="Never"/>
<disable_collisions link1="joint1" link2="joint4" reason="Never"/>
<disable_collisions link1="joint1" link2="joint5" reason="Default"/>
<disable_collisions link1="joint1" link2="joint6" reason="Never"/>
<disable_collisions link1="joint1" link2="joint6_flange" reason="Never"/>
<disable_collisions link1="joint2" link2="joint3" reason="Adjacent"/>
<disable_collisions link1="joint2" link2="joint5" reason="Never"/>
<disable_collisions link1="joint3" link2="joint4" reason="Adjacent"/>
<disable_collisions link1="joint3" link2="joint5" reason="Never"/>
<disable_collisions link1="joint4" link2="joint5" reason="Adjacent"/>
<disable_collisions link1="joint4" link2="joint6" reason="Never"/>
<disable_collisions link1="joint5" link2="joint6" reason="Adjacent"/>
<disable_collisions link1="joint5" link2="joint6_flange" reason="Never"/>
<disable_collisions link1="joint6" link2="joint6_flange" reason="Adjacent"/>
</robot>
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 70e59b5

Please sign in to comment.