Skip to content
This repository was archived by the owner on May 9, 2024. It is now read-only.

Commit 4299423

Browse files
committed
add mra6 configuration
1 parent c52915a commit 4299423

10 files changed

+347
-3
lines changed
+13
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
mra6:
2+
3+
joint_names:
4+
- J1
5+
- J2
6+
- J3
7+
- J4
8+
- J5
9+
- J6
10+
11+
12+
CAN_NODE_DEV: /dev/pcan32
13+

mra_basic/include/mra_basic/config.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ const std::vector<std::string> L_joint_names{"lJoint1","lJoint2","lJoint3","lJoi
5252

5353

5454
/**
55-
* @brief get_param
55+
* @brief get_paramc
5656
* get param set in the basic_config.yaml
5757
* Note:using inline is helpful to avoid multiple define in complile both joint_control and control_panel.
5858
*/
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,129 @@
1+
mra6:
2+
# Publish all joint states -----------------------------------
3+
joint_state_controller:
4+
type: joint_state_controller/JointStateController
5+
publish_rate: 50
6+
7+
# Mode controllers used to switch between control methods ----------------------------
8+
position_joint_mode_controller:
9+
type: joint_mode_controller/JointModeController
10+
joint_mode: 1 # position
11+
12+
velocity_joint_mode_controller:
13+
type: joint_mode_controller/JointModeController
14+
joint_mode: 2 # velocity
15+
16+
# Position - Right and Left Joint Position Trajectory Controllers -------------------
17+
arm_trajectory_controller:
18+
type: "position_controllers/JointTrajectoryController"
19+
joints:
20+
- J1
21+
- J2
22+
- J3
23+
- J4
24+
- J5
25+
- J6
26+
27+
constraints:
28+
goal_time: 2.0 # Defaults to zero
29+
stopped_velocity_tolerance: 0.1 # Defaults to 0.01
30+
J1:
31+
trajectory: 0
32+
goal: 0.2
33+
J2:
34+
trajectory: 0
35+
goal: 0.2
36+
J3:
37+
trajectory: 0
38+
goal: 0.2
39+
J4:
40+
trajectory: 0
41+
goal: 0.2
42+
J5:
43+
trajectory: 0
44+
goal: 0.2
45+
J6:
46+
trajectory: 0
47+
goal: 0.2
48+
49+
state_publish_rate: 50 # Defaults to 50
50+
action_monitor_rate: 20 # Defaults to 20
51+
#hold_trajectory_duration: 0 # Defaults to 0.5
52+
53+
54+
55+
# Position Controllers ---------------------------------------
56+
joint1_position_controller:
57+
type: position_controllers/JointPositionController
58+
joint: J1
59+
pid: {p: 100.0, i: 0.01, d: 10.0}
60+
joint2_position_controller:
61+
type: position_controllers/JointPositionController
62+
joint: J2
63+
pid: {p: 100.0, i: 0.01, d: 10.0}
64+
joint3_position_controller:
65+
type: position_controllers/JointPositionController
66+
joint: J3
67+
pid: {p: 100.0, i: 0.01, d: 10.0}
68+
joint4_position_controller:
69+
type: position_controllers/JointPositionController
70+
joint: J4
71+
pid: {p: 100.0, i: 0.01, d: 10.0}
72+
joint5_position_controller:
73+
type: position_controllers/JointPositionController
74+
joint: J5
75+
pid: {p: 100.0, i: 0.01, d: 10.0}
76+
joint6_position_controller:
77+
type: position_controllers/JointPositionController
78+
joint: J6
79+
pid: {p: 100.0, i: 0.01, d: 10.0}
80+
81+
82+
# Velocity - Joint Velocity Trajectory Controllers -------------------
83+
arm_velocity_trajectory_controller:
84+
type: "velocity_controllers/JointTrajectoryController"
85+
joints:
86+
- J1
87+
- J2
88+
- J3
89+
- J4
90+
- J5
91+
- J6
92+
93+
constraints:
94+
goal_time: 2.0 # Defaults to zero
95+
stopped_velocity_tolerance: 0.4 # Defaults to 0.01
96+
J1:
97+
trajectory: 0
98+
goal: 0.2
99+
J2:
100+
trajectory: 0
101+
goal: 0.2
102+
J3:
103+
trajectory: 0
104+
goal: 0.2
105+
J4:
106+
trajectory: 0
107+
goal: 0.2
108+
J5:
109+
trajectory: 0
110+
goal: 0.2
111+
J6:
112+
trajectory: 0
113+
goal: 0.2
114+
115+
gains:
116+
J1: {p: 2.0, i: 0.01, d: 1.0, i_clamp: 1}
117+
J2: {p: 3.0, i: 0.01, d: 1.0, i_clamp: 1}
118+
J3: {p: 3.0, i: 0.01, d: 1.0, i_clamp: 1}
119+
J4: {p: 3.0, i: 0.01, d: 1.0, i_clamp: 1}
120+
J5: {p: 3.0, i: 0.01, d: 1.0, i_clamp: 1}
121+
J6: {p: 3.0, i: 0.01, d: 1.0, i_clamp: 1}
122+
123+
state_publish_rate: 50 # Defaults to 50
124+
action_monitor_rate: 20 # Defaults to 20
125+
#hold_trajectory_duration: 0 # Defaults to 0.5
126+
127+
128+
129+
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
<?xml version="1.0" encoding="utf-8"?>
2+
<launch>
3+
4+
<!-- <group ns="robot"> -->
5+
6+
<!--Open a new terminal to execute the joint_control node
7+
<node name="mra_joint_control" pkg="mra_basic" type="joint_control" respawn="false"
8+
launch-prefix="gnome-terminal -e"/>
9+
-->
10+
<!-- Load mra_basic configurations from YAML file to parameter server -->
11+
<rosparam file="$(find mra_basic)/config/basic_config_mra6.yaml" command="load" />
12+
<!--control the real MRA by canbus.-->
13+
<node name="mra_joint_control" pkg="mra_basic" type="joint_control" respawn="false" ns="mra6"/>
14+
15+
16+
<!-- GDB functionality -->
17+
<arg name="debug" default="false" />
18+
<arg unless="$(arg debug)" name="launch_prefix" value="" />
19+
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
20+
21+
<!-- Load the URDF into the ROS Parameter Server -->
22+
<param name="robot_description"
23+
command="cat '$(find mra6_description)/urdf/mra6.urdf'" />
24+
25+
<!-- Load joint controller configurations from YAML file to parameter server -->
26+
<rosparam file="$(find mra_control)/config/mra6_hardware_controllers.yaml" command="load"/>
27+
28+
29+
<!-- Load the default controllers
30+
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
31+
output="screen" ns="mra7a" args="position_joint_mode_controller
32+
arm_trajectory_controller -->
33+
<!--timeout 50" />-->
34+
35+
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
36+
output="screen" ns="mra6" args="position_joint_mode_controller
37+
joint_state_controller
38+
joint1_position_controller
39+
joint2_position_controller
40+
joint3_position_controller
41+
joint4_position_controller
42+
joint5_position_controller
43+
joint6_position_controller
44+
--timeout 50" />
45+
46+
47+
<!-- Load hardware interface-->
48+
<node name="mra_hardware_interface" pkg="mra_control" type="mra_hardware_interface"
49+
respawn="false" output="screen" ns="mra6" launch-prefix="$(arg launch_prefix)">
50+
</node>
51+
52+
53+
54+
55+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
<?xml version="1.0" encoding="utf-8"?>
2+
<launch>
3+
4+
<!-- <group ns="robot"> -->
5+
6+
<!-- Load mra_basic configurations from YAML file to parameter server -->
7+
<rosparam file="$(find mra_basic)/config/basic_config_mra6.yaml" command="load" />
8+
9+
<!-- GDB functionality -->
10+
<arg name="debug" default="false" />
11+
<arg unless="$(arg debug)" name="launch_prefix" value="" />
12+
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
13+
14+
<!-- Load the URDF into the ROS Parameter Server -->
15+
<param name="robot_description"
16+
command="cat '$(find mra6_description)/urdf/mra6.urdf'" />
17+
18+
<!-- Load joint controller configurations from YAML file to parameter server -->
19+
<rosparam file="$(find mra_control)/config/mra6_hardware_controllers.yaml" command="load"/>
20+
21+
22+
<!-- Load the default controllers
23+
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
24+
output="screen" ns="mra7a" args="position_joint_mode_controller
25+
arm_trajectory_controller -->
26+
<!--timeout 50" />-->
27+
28+
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
29+
output="screen" ns="mra6" args="position_joint_mode_controller
30+
joint_state_controller
31+
joint1_position_controller
32+
joint2_position_controller
33+
joint3_position_controller
34+
joint4_position_controller
35+
joint5_position_controller
36+
joint6_position_controller
37+
--timeout 50" />
38+
39+
40+
<!-- Load hardware interface-->
41+
<node name="mra_hardware_interface" pkg="mra_control" type="mra_hardware_interface"
42+
respawn="false" output="screen" ns="mra6" launch-prefix="$(arg launch_prefix)">
43+
</node>
44+
45+
<!--Simulate MRA_API to send joint state and mra state-->
46+
<node name="mra_joint_state_publisher" pkg="mra_joint_state_publisher" type="mra_joint_state_publisher_node" respawn="false"
47+
output="screen" ns="mra6"/>
48+
49+
50+
51+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
<?xml version="1.0" encoding="utf-8"?>
2+
<launch>
3+
4+
<!-- <group ns="robot"> -->
5+
6+
<!--Open a new terminal to execute the joint_control node
7+
<node name="mra_joint_control" pkg="mra_basic" type="joint_control" respawn="false"
8+
launch-prefix="gnome-terminal -e"/>
9+
-->
10+
11+
<!-- Load mra_basic configurations from YAML file to parameter server -->
12+
<rosparam file="$(find mra_basic)/config/basic_config_mra6.yaml" command="load" />
13+
<!--control the real MRA by canbus.-->
14+
<node name="mra_joint_control" pkg="mra_basic" type="joint_control" respawn="false" output="screen" ns="mra7a"/>
15+
16+
<!-- GDB functionality -->
17+
<arg name="debug" default="false" />
18+
<arg unless="$(arg debug)" name="launch_prefix" value="" />
19+
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
20+
21+
<!-- Load the URDF into the ROS Parameter Server -->
22+
<param name="robot_description"
23+
command="cat '$(find mra6_description)/urdf/mra6.urdf'" />
24+
25+
<!-- Load joint controller configurations from YAML file to parameter server -->
26+
<rosparam file="$(find mra_control)/config/mra6_hardware_controllers.yaml" command="load"/>
27+
28+
29+
<!-- Load the default controllers -->
30+
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
31+
output="screen" ns="mra6" args="position_joint_mode_controller
32+
joint_state_controller
33+
arm_trajectory_controller
34+
--timeout 50" />
35+
36+
<!-- Load hardware interface-->
37+
<node name="mra_hardware_interface" pkg="mra_control" type="mra_hardware_interface"
38+
respawn="false" output="screen" ns="mra6">
39+
</node>
40+
41+
42+
43+
44+
45+
46+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
<?xml version="1.0" encoding="utf-8"?>
2+
<launch>
3+
4+
<!-- <group ns="robot"> -->
5+
6+
<!-- Load mra_basic configurations from YAML file to parameter server -->
7+
<rosparam file="$(find mra_basic)/config/basic_config_mra6.yaml" command="load" />
8+
9+
<!-- GDB functionality -->
10+
<arg name="debug" default="false" />
11+
<arg unless="$(arg debug)" name="launch_prefix" value="" />
12+
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
13+
14+
<!-- Load the URDF into the ROS Parameter Server -->
15+
<param name="robot_description"
16+
command="cat '$(find mra6_description)/urdf/mra6.urdf'" />
17+
18+
<!-- Load joint controller configurations from YAML file to parameter server -->
19+
<rosparam file="$(find mra_control)/config/mra6_hardware_controllers.yaml" command="load"/>
20+
21+
22+
<!-- Load the default controllers -->
23+
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
24+
output="screen" ns="mra6" args="position_joint_mode_controller
25+
joint_state_controller
26+
arm_trajectory_controller
27+
--timeout 50" />
28+
29+
<!-- Load hardware interface-->
30+
<node name="mra_hardware_interface" pkg="mra_control" type="mra_hardware_interface"
31+
respawn="false" output="screen" ns="mra6" launch-prefix="$(arg launch_prefix)">
32+
</node>
33+
34+
<!--Simulator MRA_API to send joint state and mra state-->
35+
<node name="mra_joint_state_publisher" pkg="mra_joint_state_publisher" type="mra_joint_state_publisher_node" respawn="false"
36+
output="screen" ns="mra6"/>
37+
38+
39+
40+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
<?xml version="1.0" encoding="utf-8"?>
2+
<launch>
3+
<include file="$(find mra_control)/launch/mra6/mra6_hw_trajectory_bingup.launch">
4+
</include>
5+
6+
<include file="$(find mra6_bringup)/launch/mra6_bringup_rviz.launch">
7+
</include>
8+
9+
10+
</launch>

mra_control/launch/mra7a/mra7a_hw_position_bingup_test.launch

+1-1
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@
4545

4646
<!--Simulate MRA_API to send joint state and mra state-->
4747
<node name="mra_joint_state_publisher" pkg="mra_joint_state_publisher" type="mra_joint_state_publisher_node" respawn="false"
48-
output="screen"/>
48+
output="screen" ns="mra7a"/>
4949

5050

5151

mra_joint_state_publisher/src/mra_joint_state_publisher_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ using namespace mra_basic_config;
1010
sensor_msgs::JointState joints;
1111

1212
void callBack(const mra_core_msgs::JointCommand &msg) {
13-
for (int i=0; i<jointID.size(); i++) {
13+
for (int i=0; i<joint_names.size(); i++) {
1414
joints.position[i] = msg.command[i];
1515
joints.velocity[i] = 0.00;
1616
joints.effort[i] = 0.000;

0 commit comments

Comments
 (0)