Skip to content
This repository was archived by the owner on Dec 1, 2020. It is now read-only.

Commit 6417a8a

Browse files
committed
Change IU torque to Ampere
1 parent 070de04 commit 6417a8a

File tree

9 files changed

+33
-18
lines changed

9 files changed

+33
-18
lines changed

march_hardware/include/march_hardware/motor_controller/imotioncube/imotioncube.h

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ class IMotionCube : public MotorController, public Slave
7171

7272
void setControlWord(uint16_t control_word);
7373
virtual void actuateRad(double target_rad) override;
74-
virtual void actuateTorque(int16_t target_torque) override;
74+
virtual void actuateTorque(double target_torque_ampere) override;
7575

7676
bool initialize(int cycle_time) override;
7777
void goToTargetState(IMotionCubeTargetState target_state);
@@ -97,7 +97,9 @@ class IMotionCube : public MotorController, public Slave
9797
constexpr static double MAX_TARGET_DIFFERENCE = 0.393;
9898
// This value is slightly larger than the current limit of the
9999
// linear joints defined in the URDF.
100-
const static int16_t MAX_TARGET_TORQUE = 23500;
100+
constexpr static double IPEAK = 40;
101+
// See CoE manual page 222
102+
constexpr static double AMPERE_TO_IU_FACTOR = 65520;
101103

102104
// Watchdog base time = 1 / 25 MHz * (2498 + 2) = 0.0001 seconds=100 µs
103105
static const uint16_t WATCHDOG_DIVIDER = 2498;
@@ -111,6 +113,7 @@ class IMotionCube : public MotorController, public Slave
111113

112114
private:
113115
void actuateIU(int32_t target_iu);
116+
int16_t ampereToTorqueIU(double ampere);
114117

115118
void mapMisoPDOs(SdoSlaveInterface& sdo);
116119
void mapMosiPDOs(SdoSlaveInterface& sdo);

march_hardware/include/march_hardware/motor_controller/motor_controller.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ class MotorController
3636
virtual bool getIncrementalMorePrecise() const = 0;
3737

3838
virtual void actuateRad(double target_rad) = 0;
39-
virtual void actuateTorque(int16_t target_torque) = 0;
39+
virtual void actuateTorque(double target_torque_ampere) = 0;
4040

4141
virtual void prepareActuation() = 0;
4242
virtual bool initialize(int cycle_time) = 0;

march_hardware/include/march_hardware/motor_controller/odrive/odrive_enums.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
#define O_PM_ENCODER_POSITION_UI ".encoder.pos_estimate"
88
#define O_PM_ENCODER_VELOCITY_UI ".encoder.vel_estimate"
99
#define O_PM_ODRIVE_INPUT_VOLTAGE "vbus_voltage"
10+
#define O_PM_DESIRED_MOTOR_CURRENT ".motor.current_control.Iq_setpoint"
1011
#define O_PM_ACTUAL_MOTOR_CURRENT ".motor.current_control.Iq_measured"
1112
#define O_PM_ACTUAL_MOTOR_VOLTAGE_D ".motor.current_control.v_current_control_integral_d"
1213
#define O_PM_ACTUAL_MOTOR_VOLTAGE_Q ".motor.current_control.v_current_control_integral_q"

march_hardware/include/march_hardware/motor_controller/odrive/odrive_motor.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ class OdriveMotor : public Odrive
2525
void reset() override;
2626

2727
void actuateRad(double target_rad) override;
28-
void actuateTorque(int16_t target_torque) override;
28+
void actuateTorque(double target_torque_ampere) override;
2929

3030
MotorControllerStates& getStates() override;
3131

march_hardware/src/imotioncube/imotioncube.cpp

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -184,21 +184,22 @@ void IMotionCube::actuateIU(int32_t target_iu)
184184
this->write32(target_position_location, target_position);
185185
}
186186

187-
void IMotionCube::actuateTorque(int16_t target_torque)
187+
void IMotionCube::actuateTorque(double target_torque_ampere)
188188
{
189+
if (target_torque_ampere >= IPEAK)
190+
{
191+
throw error::HardwareException(error::ErrorType::TARGET_TORQUE_EXCEEDS_MAX_TORQUE,
192+
"Target torque of %dA exceeds max torque of %dA", target_torque_ampere, IPEAK);
193+
}
194+
int16_t target_torque = ampereToTorqueIU(target_torque_ampere);
195+
189196
if (this->actuation_mode_ != ActuationMode::torque)
190197
{
191198
throw error::HardwareException(error::ErrorType::INVALID_ACTUATION_MODE,
192199
"trying to actuate torque, while actuation mode is %s",
193200
this->actuation_mode_.toString().c_str());
194201
}
195202

196-
if (target_torque >= MAX_TARGET_TORQUE)
197-
{
198-
throw error::HardwareException(error::ErrorType::TARGET_TORQUE_EXCEEDS_MAX_TORQUE,
199-
"Target torque of %d exceeds max torque of %d", target_torque, MAX_TARGET_TORQUE);
200-
}
201-
202203
bit16 target_torque_struct = { .i = target_torque };
203204

204205
uint8_t target_torque_location = this->mosi_byte_offsets_.at(IMCObjectName::TargetTorque);
@@ -554,4 +555,10 @@ ActuationMode IMotionCube::getActuationMode() const
554555
{
555556
return this->actuation_mode_;
556557
}
558+
559+
int16_t IMotionCube::ampereToTorqueIU(double ampere)
560+
{
561+
// See CoE manual page 222
562+
return AMPERE_TO_IU_FACTOR * ampere / (2 * IPEAK);
563+
}
557564
} // namespace march

march_hardware/src/odrive/odrive_motor.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,10 +36,14 @@ void OdriveMotor::actuateRad(double target_rad)
3636
return;
3737
}
3838

39-
void OdriveMotor::actuateTorque(int16_t target_torque)
39+
void OdriveMotor::actuateTorque(double target_torque_ampere)
4040
{
41-
ROS_INFO("Actuating torque %d", target_torque);
42-
return;
41+
float target_torque_ampere_float = (float) target_torque_ampere;
42+
std::string command_name_ = this->create_command(O_PM_DESIRED_MOTOR_CURRENT);
43+
if (this->write(command_name_, target_torque_ampere_float) == 1)
44+
{
45+
ROS_ERROR("Could net set target torque; %f to the axis", target_torque_ampere);
46+
}
4347
}
4448

4549
MotorControllerStates& OdriveMotor::getStates()

march_hardware/test/mocks/mock_motor_controller.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ class MockMotorController : public march::MotorController
3333
MOCK_METHOD0(getTorque, double());
3434

3535
MOCK_METHOD1(actuateRad, void(double));
36-
MOCK_METHOD1(actuateTorque, void(int16_t));
36+
MOCK_METHOD1(actuateTorque, void(double));
3737

3838
MOCK_METHOD1(initialize, bool(int cycle_time));
3939
MOCK_METHOD0(reset, void());

march_hardware_interface/include/march_hardware_interface/march_hardware_interface.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -90,8 +90,8 @@ class MarchHardwareInterface : public hardware_interface::RobotHW
9090
static void getSoftJointLimitsError(const std::string& name, const urdf::JointConstSharedPtr& urdf_joint,
9191
joint_limits_interface::SoftJointLimits& error_soft_limits);
9292

93-
/* Limit of the change in effort command over one cycle, can be overridden by safety controller */
94-
static constexpr double MAX_EFFORT_CHANGE = 5000;
93+
/* Limit of the change (ampere) in effort command over one cycle, can be overridden by safety controller */
94+
static constexpr double MAX_EFFORT_CHANGE = 6;
9595

9696
/* March hardware */
9797
std::unique_ptr<march::MarchRobot> march_robot_;

march_hardware_interface/src/march_hardware_interface.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -231,7 +231,7 @@ void MarchHardwareInterface::write(const ros::Time& /* time */, const ros::Durat
231231
for (size_t i = 0; i < num_joints_; i++)
232232
{
233233
// Enlarge joint_effort_command because ROS control limits the pid values to a certain maximum
234-
joint_effort_command_[i] = joint_effort_command_[i] * 1000.0;
234+
joint_effort_command_[i] = joint_effort_command_[i];
235235
if (std::abs(joint_last_effort_command_[i] - joint_effort_command_[i]) > MAX_EFFORT_CHANGE)
236236
{
237237
joint_effort_command_[i] =

0 commit comments

Comments
 (0)