Skip to content

Commit fea3c8a

Browse files
committed
fix hero chassis
1 parent 2868b46 commit fea3c8a

File tree

4 files changed

+22
-6
lines changed

4 files changed

+22
-6
lines changed

decomposition/metav_description/urdf/hero/hero.xacro

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
<ros2_control name="dji_motors_chassis" type="system">
3838
<hardware>
3939
<plugin>meta_hardware/MetaRobotDjiMotorNetwork</plugin>
40-
<param name="can_network_name">can1</param>
40+
<param name="can_network_name">can_1</param>
4141
</hardware>
4242
<xacro:wheel_transmission prefix="front_left" mechanical_reduction="20.0" motor_id="1" />
4343
<xacro:wheel_transmission prefix="front_right" mechanical_reduction="20.0" motor_id="2" />
@@ -50,15 +50,17 @@
5050
<ros2_control name="dm_motors_yaw" type="system">
5151
<hardware>
5252
<plugin>meta_hardware/MetaRobotDjiMotorNetwork</plugin>
53-
<param name="can_network_name">can1</param>
53+
<param name="can_network_name">can_1</param>
5454
</hardware>
55-
<xacro:gimbal_transmission prefix="pitch" mechanical_reduction="20.0" motor_id="1" offset="0"/>
55+
<xacro:gimbal_transmission prefix="pitch" mechanical_reduction="20.0" motor_id="7" offset="0"/>
56+
<xacro:gimbal_transmission prefix="yaw" mechanical_reduction="20.0" motor_id="8" offset="0"/>
57+
5658
</ros2_control>
5759

5860
<ros2_control name="dji_motors_gimbal" type="system">
5961
<hardware>
6062
<plugin>meta_hardware/MetaRobotDjiMotorNetwork</plugin>
61-
<param name="can_network_name">can2</param>
63+
<param name="can_network_name">can_2</param>
6264
</hardware>
6365
<xacro:shooter_transmission prefix="fric1" mechanical_reduction="-1.0" offset="0.25" motor_model="M3508"
6466
motor_id="4" />

decomposition/metav_description/urdf/standard/standard.shooter.xacro

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -89,13 +89,13 @@
8989
</xacro:macro>
9090

9191
<xacro:macro name="shooter_transmission"
92-
params="prefix mechanical_reduction offset motor_id">
92+
params="prefix mechanical_reduction offset motor_id motor_model">
9393
<joint name="${prefix}_shooter_joint">
9494
<command_interface name="effort" />
9595
<state_interface name="position" />
9696
<state_interface name="velocity" />
9797
<state_interface name="effort" />
98-
<param name="motor_model">M2006</param>
98+
<param name="motor_model">${motor_model}</param>
9999
<param name="motor_id">${motor_id}</param>
100100
<param name="mechanical_reduction">${mechanical_reduction}</param>
101101
<param name="offset">${offset}</param>

rules/01-robomaster-host1ton.rules

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
# udev file for host1toN v0.2
2+
DEVPATH=="/devices/*.1:1.0/net/can*", NAME="can_2", MODE="0666"
3+
DEVPATH=="/devices/*.2:1.0/net/can*", NAME="can_1", MODE="0666"
4+
DEVPATH=="/devices/*.3.2:1.0/net/can*", NAME="can_3", MODE="0666"
5+
DEVPATH=="/devices/*.3.3:1.0/tty*", SYMLINK+="tty_RS485_1", MODE="0666"
6+
DEVPATH=="/devices/*.3.3:1.1/tty*", SYMLINK+="tty_RS485_2", MODE="0666"
7+
DEVPATH=="/devices/*.3.1:1.0/tty*", SYMLINK+="tty_REF", MODE="0666"
8+
DEVPATH=="/devices/*.4.1:1.0/tty*", SYMLINK+="tty_VT02", MODE="0666"
9+
DEVPATH=="/devices/*.4.2:1.0/tty*", SYMLINK+="tty_DBUS", MODE="0666"
10+
DEVPATH=="/devices/*.4.4:1.0/tty*", SYMLINK+="tty_IMU", MODE="0666"
11+

rules/install.sh

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
#!/bin/sh
2+
sudo cp 01-robomaster-host1ton.rules /etc/udev/rules.d/
3+
sudo udevadm control --reload && sudo udevadm trigger

0 commit comments

Comments
 (0)