Skip to content

Commit d56aa67

Browse files
committed
dm motor typo fix
1 parent 4e864b7 commit d56aa67

File tree

2 files changed

+8
-8
lines changed

2 files changed

+8
-8
lines changed

decomposition/metav_description/urdf/playground/dm_motor.xacro

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -38,21 +38,21 @@
3838
<hardware>
3939
<plugin>meta_hardware/MetaRobotDmMotorNetwork</plugin>
4040
<param name="can_network_name">can0</param>
41-
<param name="master_id">0</param>
41+
<param name="master_id">0x30</param>
4242
</hardware>
4343
<joint name="motor_joint">
4444
<command_interface name="position" />
4545
<state_interface name="position" />
4646
<state_interface name="velocity" />
4747
<state_interface name="effort" />
48-
<param name="motor_model">4310</param>
48+
<param name="motor_model">DaMiao</param>
4949
<param name="motor_id">2</param>
5050
<param name="mechanical_reduction">1.0</param>
5151
<param name="max_pos">3.141593</param>
5252
<param name="max_vel">30</param>
5353
<param name="max_effort">10</param>
5454
<param name="offset">0.0</param>
55-
<param name="control_mode">position</param>
55+
<param name="control_mode">mit</param>
5656
<param name="Kp">150.0</param>
5757
<param name="Kd">0.5</param>
5858
</joint>

execution/meta_hardware/src/motor_driver/dm_motor_driver.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ DmMotor::DmMotor(const std::unordered_map<std::string, std::string> &motor_param
3333
max_effort_ = std::stod(motor_param.at("max_effort"));
3434

3535
std::string control_mode = motor_param.at("control_mode");
36-
uint32_t id_offeset = 0;
36+
uint32_t id_offset = 0;
3737

3838
if (control_mode == "mit") {
3939
Kp_ = std::stod(motor_param.at("Kp"));
@@ -46,16 +46,16 @@ DmMotor::DmMotor(const std::unordered_map<std::string, std::string> &motor_param
4646

4747
} else if (control_mode == "position") {
4848
run_mode_ = RunMode::POSITION;
49-
id_offeset = 0x100;
49+
id_offset = 0x100;
5050
} else if (control_mode == "velocity") {
5151
run_mode_ = RunMode::VELOCITY;
52-
id_offeset = 0x200;
52+
id_offset = 0x200;
5353
} else {
5454
throw std::runtime_error("Unknown motor mode: " + control_mode);
5555
}
5656

57-
if (motor_model_ == "4310") {
58-
tx_can_id_ = dm_motor_id_ + id_offeset;
57+
if (motor_model_ == "DaMiao") {
58+
tx_can_id_ = dm_motor_id_ + id_offset;
5959
} else {
6060
throw std::runtime_error("Unknown motor model: " + motor_model_);
6161
}

0 commit comments

Comments
 (0)