Skip to content

Commit ffd3ef6

Browse files
author
YH.Wang
committed
1.2.0 Add tm12s and tm25s moveit configuration, launch files and relative README.md.
1 parent 4917309 commit ffd3ef6

Some content is hidden

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

64 files changed

+4014
-2
lines changed

README.md

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -126,6 +126,14 @@ This chapter describes that the user can use a script program to extract specifi
126126
**Note 2**: The tm_description package contains description files and meshes, available for the TM5S, TM7S, TM12S, TM14S, and TM25S model, and some Cobot models will be added later.
127127
<div> </div>
128128

129-
## __7. Contact us / Technical support__
129+
## __7. Related ROS Projects and Tutorials Usage__
130+
&#10148; For example, you can try to run __MoveIt__ on the TM robot
131+
The user can use MoveIt to control the TM robot in the motion planning to plan paths or run the TM Robot simulation into your scene description for operations such as _collision checking_ or _obstacle avoidance_.
132+
See [MoveIt2 tutorial](https://moveit.ros.org/install-moveit2/binary/) to install the MoveIt2 packages.<br/>
133+
- External TM ROS Driver [Usage Guideline](./doc/tm_humble_extension.md)
134+
- Embedded TM ROS Driver [Usage Guideline](./doc/tm_humble_extension_e.md)
135+
<div> </div>
136+
137+
## __8. Contact us / Technical support__
130138
More Support & Service, please contact us. [@TECHMAN ROBOT](https://www.tm-robot.com/zh-hant/contact-us/)``[https://www.tm-robot.com/zh-hant/contact-us/] ``<br/>
131139
<div> </div>

doc/tm_humble_extension.md

Lines changed: 105 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
# __Related Projects and Tutorials Usage__
2+
## &sect; ROS2 driver usage
3+
>
4+
> After the user has set up the ROS2 environment (example : [Debian packages for ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html)) and built the TM driver based on the specific workspace, please enter your workspace `<workspace>` by launching the terminal, and remember to make the workspace visible to ROS.
5+
>
6+
>
7+
> ```bash
8+
> source /opt/ros/humble/setup.bash
9+
> cd <workspace>
10+
> source ./install/setup.bash
11+
> ```
12+
> :bulb: Do you prepare the __TM Robot__ ready ? Make sure that TM Robot's operating software (__TMflow__) network settings are ready and the __Listen node__ is running.
13+
>
14+
> Then, run the driver to test whether the complete communication interface is properly working with TM Robot by typing
15+
>
16+
>```bash
17+
> ros2 run tm_driver tm_driver robot_ip:=<robot_ip_address>
18+
>```
19+
> Example :``ros2 run tm_driver tm_driver robot_ip:=192.168.10.2``, if the <robot_ip_address> is 192.168.10.2
20+
>
21+
> Now, the user can use a new terminal to run each ROS node or command, but don't forget to source the correct setup shell files as starting a new terminal.
22+
> Note: When you finish executing your developed scripts or motion commands through the TM ROS driver connection, press CTRL + C in all terminal windows to shut everything down.
23+
24+
## &sect; Usage with MoveIt2-humble (Binary)
25+
>
26+
> See [MoveIt2 tutorial](https://moveit.ros.org/install-moveit2/binary/) to install the MoveIt2 packages.<br/>
27+
> ```bash
28+
> sudo apt install ros-humble-moveit
29+
> ```
30+
> Then, use the following command to install these ROS2 Humble dependency packages
31+
> ```bash
32+
> sudo apt-get install ros-humble-controller-manager
33+
> sudo apt install ros-humble-joint-trajectory-controller
34+
> sudo apt install ros-humble-joint-state-broadcaster
35+
> ```
36+
>
37+
> If you plan to use MoveIt, it is recommended to install and use Cyclone DDS.
38+
> ```bash
39+
> sudo apt install ros-$ROS_DISTRO-rmw-cyclonedds-cpp
40+
> export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
41+
> ```
42+
>
43+
> The `<tm2_ws>` means TM driver workspace, for example `tm2_ws` .<br/>
44+
>
45+
>
46+
> Then to build the TM driver based on the <tm2_ws> workspace, please enter the specific workspace `tm2_ws` by launching the terminal, and remember to make the workspace visible to ROS.<br/>
47+
>
48+
>
49+
> ```bash
50+
> source /opt/ros/humble/setup.bash
51+
> export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
52+
> cd ~/tm2_ws
53+
> colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
54+
> source ./install/setup.bash
55+
> ```
56+
>
57+
> :bulb: If you have built the TM driver before, it is recommended that you delete the build, install and log folders by the command `rm -rf build install log`, and rebuild it. For example,<br/>
58+
>
59+
>
60+
> ```bash
61+
> source /opt/ros/humble/setup.bash
62+
> export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
63+
> cd ~/tm2_ws
64+
> rm -rf build install log
65+
> colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
66+
> source ./install/setup.bash
67+
> ```
68+
>
69+
> The demo launches the RViz GUI and demonstrates planning and execution of a simple collision-free motion plan with TM Robot.<br/>
70+
> :bulb: Do you prepare the __TM Robot__ ready ? Make sure that TM Robot's operating software (__TMflow__) network settings are ready and the __Listen node__ is running.<br/>
71+
>
72+
> * To bring up the MoveIt2 - MoveGroup demo in simulation mode with the virtual TM Robot, by typing<br/>
73+
>
74+
>
75+
> ```bash
76+
> ros2 launch <tm_robot_type>_moveit_config <tm_robot_type>_run_move_group.launch.py
77+
> ```
78+
>
79+
>> The prefix `<tm_robot_type>` means the TM Robot type, available for tm5s, tm7s, tm12s, tm14s, and tm25s models.
80+
>
81+
> Taking the TM12S robot as an example, use the commands introduced above, by typing
82+
> ```bash
83+
> ros2 launch tm12s_moveit_config tm12s_run_move_group.launch.py
84+
> ```
85+
>
86+
> * The user can also manipulate the real TM Robot to run, by typing<br/>
87+
>
88+
> ```bash
89+
> roslaunch <tm_robot_type>_moveit_config <tm_robot_type>_run_move_group.launch.py robot_ip:=<robot_ip_address>
90+
> ```
91+
> :warning:[CAUTION] This demo will let the real TM Robot move, please be careful. If the user are a beginner or unfamiliar with the arm movement path, it is recommended that the user place your hand on the big red emergency _Stick Stop Button_ at any time, and press the button appropriately in the event of any accident that may occur.<br/>
92+
>
93+
> Taking the TM12S robot as an example, use the commands introduced above, by typing<br/>
94+
>
95+
> ```bash
96+
> ros2 launch tm12s_moveit_config tm12s_run_move_group.launch.py robot_ip:=<robot_ip_address>
97+
> ```
98+
>
99+
>> The parameter `<robot_ip_address>` means the IP address of the TM Robot.<br/>
100+
>
101+
> 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/>
103+
> :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/>
104+
<div> </div>
105+

doc/tm_humble_extension_e.md

Lines changed: 98 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,98 @@
1+
# __Related Projects and Tutorials Usage__
2+
## &sect; ROS2 driver usage
3+
>
4+
> :bulb: Do you prepare the __TM Robot__ ready ? Make sure that TM Robot's operating software (__TMflow__) network settings and __ROS Settings__ _(ROS Drive status: &rArr; __`Running`__)_ are ready and the __Listen node__ is running. Do you build TM relative ROS apps <sup>1</sup> on your (remote) computer?
5+
> After the user has set up the ROS2 environment (example : [Debian packages for ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html)) and built the TM relative ROS apps <sup>1</sup> based on the specific workspace, please enter your workspace `<workspace>` by launching the terminal, and remember to make the workspace visible to ROS.
6+
>
7+
>
8+
> ```bash
9+
> source /opt/ros/humble/setup.bash
10+
> cd <workspace>
11+
> export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
12+
> export ROS_DOMAIN_ID=<ROS_DOMAIN_ID>
13+
> source ./install/setup.bash
14+
> ```
15+
>> **Note**: Domain ID is the key to ROS communication, and please make sure the ROS node works under the ROS environment setup with the same Domain ID as the robot.
16+
>
17+
> Now, the user can use the terminal to run the ROS node or command, but don't forget to export the correct <u>Domain ID</u> setup and source the correct setup shell files as starting a new terminal.
18+
> Note: When you finish executing your developed scripts or motion commands through the TM ROS driver connection, press CTRL + C in all terminal windows to shut everything down.
19+
20+
## &sect; Usage with MoveIt2-humble (Binary)
21+
>
22+
> See [MoveIt2 tutorial](https://moveit.ros.org/install-moveit2/binary/) to install the MoveIt2 packages.<br/>
23+
> ```bash
24+
> sudo apt install ros-humble-moveit
25+
> ```
26+
> Then, use the following command to install these ROS2 Humble dependency packages
27+
> ```bash
28+
> sudo apt-get install ros-humble-controller-manager
29+
> sudo apt install ros-humble-joint-trajectory-controller
30+
> sudo apt install ros-humble-joint-state-broadcaster
31+
> ```
32+
>
33+
>
34+
> The `<tm2_ws>` means TM driver workspace, for example `tm2_ws` .<br/>
35+
>
36+
>
37+
> Then to build the TM driver based on the <tm2_ws> workspace, please enter the specific workspace `tm2_ws` by launching the terminal, and remember to make the workspace visible to ROS.<br/>
38+
>
39+
>
40+
> ```bash
41+
> source /opt/ros/humble/setup.bash
42+
> export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
43+
> cd ~/tm2_ws
44+
> colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
45+
> export ROS_DOMAIN_ID=<ROS_DOMAIN_ID>
46+
> source ./install/setup.bash
47+
> ```
48+
>
49+
> :bulb: If you have built the TM driver before, it is recommended that you delete the build, install and log folders by the command `rm -rf build install log`, and rebuild it. For example,<br/>
50+
>
51+
>
52+
> ```bash
53+
> source /opt/ros/humble/setup.bash
54+
> export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
55+
> cd ~/tm2_ws
56+
> rm -rf build install log
57+
> colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
58+
> export ROS_DOMAIN_ID=<ROS_DOMAIN_ID>
59+
> source ./install/setup.bash
60+
> ```
61+
>
62+
> The demo launches the RViz GUI and demonstrates planning and execution of a simple collision-free motion plan with TM Robot.<br/>
63+
> :bulb: Do you prepare the __TM Robot__ ready ? Make sure that TM Robot's operating software (__TMflow__) network settings are ready and the __Listen node__ is running.<br/>
64+
>
65+
> * To bring up the MoveIt2 - MoveGroup demo in simulation mode with the virtual TM Robot, by typing<br/>
66+
>
67+
>
68+
> ```bash
69+
> ros2 launch <tm_robot_type>_moveit_config <tm_robot_type>_run_move_group.launch.py
70+
> ```
71+
>
72+
>> The prefix `<tm_robot_type>` means the TM Robot type, available for tm5s, tm7s, tm12s, tm14s, and tm25s models.
73+
>
74+
> Taking the TM12S robot as an example, use the commands introduced above, by typing
75+
> ```bash
76+
> ros2 launch tm12s_moveit_config tm12s_run_move_group.launch.py
77+
> ```
78+
>
79+
> * The user can also manipulate the real TM Robot to run, by typing<br/>
80+
>
81+
> ```bash
82+
> roslaunch <tm_robot_type>_moveit_config <tm_robot_type>_run_move_group.launch.py robot_ip:=<robot_ip_address>
83+
> ```
84+
> :warning:[CAUTION] This demo will let the real TM Robot move, please be careful. If the user are a beginner or unfamiliar with the arm movement path, it is recommended that the user place your hand on the big red emergency _Stick Stop Button_ at any time, and press the button appropriately in the event of any accident that may occur.<br/>
85+
>
86+
> Taking the TM12S robot as an example, use the commands introduced above, by typing<br/>
87+
>
88+
> ```bash
89+
> ros2 launch tm12s_moveit_config tm12s_run_move_group.launch.py robot_ip:=<robot_ip_address>
90+
> ```
91+
>
92+
>> The parameter `<robot_ip_address>` means the IP address of the TM Robot.<br/>
93+
>
94+
> 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/>
96+
> :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/>
97+
<div> </div>
98+

tm_driver/src/tm_ros2_svr.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,7 @@ void TmSvrRos2::publish_fbs()
141141
pm.fbs_msg.joint_tor_max = state.joint_torque_max();
142142

143143
/* MC-001:start */
144-
if((state.get_receive_state() != TmCommRC::TIMEOUT) || (fbs_lock_ != false)) {
144+
if((state.get_receive_state() != TmCommRC::TIMEOUT) || (fbs_lock_ != false)) {
145145
state.mtx_unlock();
146146
fbs_lock_ = false;
147147
}
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/tm12s.urdf.xacro
5+
srdf:
6+
relative_path: config/tm12s.srdf
7+
package_settings:
8+
author_name: Yh Wang
9+
author_email: [email protected]
10+
generated_timestamp: 1719571103
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(tm12s_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
Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
2+
3+
# For beginners, we downscale velocity and acceleration limits.
4+
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
5+
default_velocity_scaling_factor: 0.1
6+
default_acceleration_scaling_factor: 0.1
7+
8+
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
9+
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
10+
joint_limits:
11+
joint_1:
12+
has_velocity_limits: true
13+
max_velocity: 2.2689280275926285
14+
has_acceleration_limits: false
15+
max_acceleration: 0
16+
joint_2:
17+
has_velocity_limits: true
18+
max_velocity: 2.2689280275926285
19+
has_acceleration_limits: false
20+
max_acceleration: 0
21+
joint_3:
22+
has_velocity_limits: true
23+
max_velocity: 3.6651914291880923
24+
has_acceleration_limits: false
25+
max_acceleration: 0
26+
joint_4:
27+
has_velocity_limits: true
28+
max_velocity: 3.9269908169872414
29+
has_acceleration_limits: false
30+
max_acceleration: 0
31+
joint_5:
32+
has_velocity_limits: true
33+
max_velocity: 3.9269908169872414
34+
has_acceleration_limits: false
35+
max_acceleration: 0
36+
joint_6:
37+
has_velocity_limits: true
38+
max_velocity: 7.8539816339744828
39+
has_acceleration_limits: false
40+
max_acceleration: 0

0 commit comments

Comments
 (0)