Skip to content

Commit b9a71a0

Browse files
author
YH.Wang
committed
1.2.1 Add tm5s, tm7s and tm14s moveit configuration, launch files, some moveit setting modifications of tm12s, tm25s and update relative README.md.
1 parent ffd3ef6 commit b9a71a0

File tree

101 files changed

+5819
-34
lines changed

Some content is hidden

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

101 files changed

+5819
-34
lines changed

doc/tm_humble_extension.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@
9999
>> The parameter `<robot_ip_address>` means the IP address of the TM Robot.<br/>
100100
>
101101
> Note: When you have finished, press CTRL + C in all terminal windows to shut everything down.<br/>
102-
> :bookmark_tabs: Note1: There will be several built-in TM Robot nominal robot model settings, available for TM5S, TM7S, TM12S, TM14S, and TM25S models.<br/>
102+
> :bookmark_tabs: Note1: There are several built-in TM Robot nominal robot model settings, available for TM5S, TM7S, TM12S, TM14S, and TM25S models.<br/>
103103
> :bookmark_tabs: Note2: TM Robot set the default to read the Xacro file, such as _TM5S_ model, to read the file _tm5s.urdf.xacro_ into robot_description or such as _TM12S_ model, to read the file _tm12s.urdf.xacro_ into robot_description. If the user wants to use the specific model parameters instead of the nominal model to control the robot, please go back to the section __6. Generate your TM Robot-Specific Kinematics Parameters Files__ to modify the Xacro file.<br/>
104104
<div> </div>
105105

doc/tm_humble_extension_e.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@
9292
>> The parameter `<robot_ip_address>` means the IP address of the TM Robot.<br/>
9393
>
9494
> Note: When you have finished, press CTRL + C in all terminal windows to shut everything down.<br/>
95-
> :bookmark_tabs: Note1: There will be several built-in TM Robot nominal robot model settings, available for TM5S, TM7S, TM12S, TM14S, and TM25S models.<br/>
95+
> :bookmark_tabs: Note1: There are several built-in TM Robot nominal robot model settings, available for TM5S, TM7S, TM12S, TM14S, and TM25S models.<br/>
9696
> :bookmark_tabs: Note2: TM Robot set the default to read the Xacro file, such as _TM5S_ model, to read the file _tm5s.urdf.xacro_ into robot_description or such as _TM12S_ model, to read the file _tm12s.urdf.xacro_ into robot_description. If the user wants to use the specific model parameters instead of the nominal model to control the robot, please go back to the section __6. Generate your TM Robot-Specific Kinematics Parameters Files__ to modify the Xacro file.<br/>
9797
<div> </div>
9898
Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
# MoveIt uses this configuration for controller management
2+
trajectory_execution:
3+
allowed_execution_duration_scaling: 1.2
4+
allowed_goal_duration_margin: 0.5
5+
allowed_start_tolerance: 0.1
6+
trajectory_duration_monitoring: false
7+
8+
moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
9+
10+
moveit_simple_controller_manager:
11+
controller_names:
12+
- tmr_arm_controller
13+
14+
tmr_arm_controller:
15+
action_ns: follow_joint_trajectory
16+
type: FollowJointTrajectory
17+
default: true
18+
joints:
19+
- joint_1
20+
- joint_2
21+
- joint_3
22+
- joint_4
23+
- joint_5
24+
- joint_6

tm_moveit/tm12s_moveit_config/config/ros2_controllers.yaml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,6 @@
22
controller_manager:
33
ros__parameters:
44
update_rate: 100 # Hz
5-
use_sim_time: true
65

76
tmr_arm_controller:
87
type: joint_trajectory_controller/JointTrajectoryController

tm_moveit/tm12s_moveit_config/launch/tm12s_moveit.launch.py

Lines changed: 10 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ def generate_launch_description():
5252
moveit_config_path = 'tm12s_moveit_config'
5353
srdf_path = 'config/tm12s.srdf'
5454
rviz_path = '/rviz/moveit.rviz'
55-
controller_path = 'config/moveit_controllers.yaml'
55+
controller_path = 'config/moveit2_controllers.yaml'
5656
joint_limits_path = 'config/joint_limits.yaml'
5757

5858
# MoveIt Configuration
@@ -65,18 +65,14 @@ def generate_launch_description():
6565
.to_moveit_configs()
6666
)
6767

68-
# moveit_config.moveit_cpp.update({"use_sim_time": use_sim_time.perform(context) == "true"})
69-
7068
# Start the actual move_group node/action server
7169
run_move_group_node = Node(
7270
package='moveit_ros_move_group',
7371
executable='move_group',
7472
output='screen',
7573
parameters=[
7674
moveit_config.to_dict(),
77-
{
78-
"use_sim_time": True,
79-
},
75+
{'use_sim_time': True},
8076
],
8177
)
8278

@@ -93,9 +89,10 @@ def generate_launch_description():
9389
parameters=[
9490
moveit_config.robot_description,
9591
moveit_config.robot_description_semantic,
96-
moveit_config.robot_description_kinematics,
9792
moveit_config.planning_pipelines,
98-
# moveit_config.joint_limits,
93+
moveit_config.robot_description_kinematics,
94+
moveit_config.joint_limits,
95+
{'use_sim_time': True},
9996
],
10097
)
10198

@@ -129,15 +126,13 @@ def generate_launch_description():
129126
ros2_control_node = Node(
130127
package='controller_manager',
131128
executable='ros2_control_node',
132-
parameters=[moveit_config.robot_description, ros2_controllers_path],
129+
parameters=[ros2_controllers_path],
130+
remappings=[
131+
('/controller_manager/robot_description', '/robot_description'),
132+
],
133133
output='both',
134134
)
135135

136-
controller_manager = Node(
137-
package="controller_manager",
138-
executable="ros2_control_node",
139-
)
140-
141136
joint_state_broadcaster_spawner = Node(
142137
package='controller_manager',
143138
executable='spawner',
@@ -153,7 +148,7 @@ def generate_launch_description():
153148
executable="spawner",
154149
arguments=[
155150
'tmr_arm_controller',
156-
'-c',
151+
'--controller-manager',
157152
'/controller_manager',
158153
],
159154
)
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
moveit_setup_assistant_config:
2+
urdf:
3+
package: tm_description
4+
relative_path: xacro/tm14s.urdf.xacro
5+
srdf:
6+
relative_path: config/tm14s.srdf
7+
package_settings:
8+
author_name: Yh Wang
9+
author_email: [email protected]
10+
generated_timestamp: 1719571375
11+
control_xacro:
12+
command:
13+
- position
14+
state:
15+
- position
16+
- velocity
17+
modified_urdf:
18+
xacros:
19+
- control_xacro
20+
control_xacro:
21+
command:
22+
- position
23+
state:
24+
- position
25+
- velocity
Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
cmake_minimum_required(VERSION 3.22)
2+
project(tm14s_moveit_config)
3+
4+
find_package(ament_cmake REQUIRED)
5+
6+
ament_package()
7+
8+
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}
9+
PATTERN "setup_assistant.launch" EXCLUDE)
10+
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
11+
install(DIRECTORY rviz DESTINATION share/${PROJECT_NAME})
12+
install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME})
Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
planning_plugin: chomp_interface/CHOMPPlanner
2+
request_adapters: >-
3+
default_planner_request_adapters/AddTimeParameterization
4+
default_planner_request_adapters/FixWorkspaceBounds
5+
default_planner_request_adapters/FixStartStateBounds
6+
default_planner_request_adapters/FixStartStateCollision
7+
default_planner_request_adapters/FixStartStatePathConstraints
8+
start_state_max_bounds_error: 0.1
9+
planning_time_limit: 10.0
10+
max_iterations: 200
11+
max_iterations_after_collision_free: 5
12+
smoothness_cost_weight: 0.1
13+
obstacle_cost_weight: 1.0
14+
learning_rate: 0.01
15+
smoothness_cost_velocity: 0.0
16+
smoothness_cost_acceleration: 1.0
17+
smoothness_cost_jerk: 0.0
18+
ridge_factor: 0.01
19+
use_pseudo_inverse: false
20+
pseudo_inverse_ridge_factor: 1e-4
21+
joint_update_limit: 0.1
22+
collision_clearance: 0.2
23+
collision_threshold: 0.07
24+
use_stochastic_descent: true
25+
enable_failure_recovery: true
26+
max_recovery_attempts: 5
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
controller_names:
2+
- tmr_arm_controller
3+
4+
tmr_arm_controller:
5+
action_ns: follow_joint_trajectory
6+
type: FollowJointTrajectory
7+
default: true
8+
joints:
9+
- joint_1
10+
- joint_2
11+
- joint_3
12+
- joint_4
13+
- joint_5
14+
- joint_6
15+
constraints:
16+
stopped_velocity_tolerance: 0.05
17+
goal_time: 0.0
Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
# Default initial positions for the TM arm's ros2_control fake system
2+
3+
initial_positions:
4+
joint_1: 0.0
5+
joint_2: 0.0
6+
joint_3: 0.0
7+
joint_4: 0.0
8+
joint_5: 0.0
9+
joint_6: 0.0

0 commit comments

Comments
 (0)