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

Commit 55c9efb

Browse files
committed
Fix merge conflicts
1 parent 7120112 commit 55c9efb

File tree

7 files changed

+32
-14
lines changed

7 files changed

+32
-14
lines changed

march_hardware/include/march_hardware/motor_controller/odrive/odrive_states.h

Lines changed: 23 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -14,18 +14,36 @@ struct OdriveStates : public MotorControllerStates
1414
OdriveStates() = default;
1515

1616
States state;
17+
uint16_t axisError;
18+
uint16_t axisMotorError;
19+
uint16_t axisEncoderError;
20+
uint16_t axisControllerError;
1721

18-
virtual bool checkState()
22+
std::string axisErrorDescription;
23+
std::string axisMotorErrorDescription;
24+
std::string axisEncoderErrorDescription;
25+
std::string axisControllerErrorDescription;
26+
27+
bool checkState() override
1928
{
20-
return true;
29+
if (this->axisError == ERROR_NONE)
30+
{
31+
return true;
32+
}
33+
return false;
2134
}
2235

23-
virtual std::string getErrorStatus()
36+
std::string getErrorStatus() override
2437
{
2538
std::ostringstream error_stream;
26-
// std::string state = IMCStateOfOperation(this->statusWord).getString().c_str();
2739

28-
error_stream << "State: " << state;
40+
error_stream << "State: " << this->state << "\nAxis Error: " << this->axisError << " ("
41+
<< this->axisErrorDescription << ")"
42+
<< "\nMotor Error: " << this->axisMotorError << " (" << this->axisMotorErrorDescription << ")"
43+
<< "\nEncoder Error: " << this->axisEncoderError << " (" << this->axisEncoderErrorDescription << ")"
44+
<< "\nController Error: " << this->axisControllerError << " (" << this->axisControllerErrorDescription
45+
<< ")";
46+
2947
return error_stream.str();
3048
}
3149
};

march_hardware_builder/robots/march3.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
march3:
22
ifName: enp3s0
3-
ecatCycleTime: 4
3+
cycleTime: 4
44
joints:
55
- right_hip:
66
actuationMode: position

march_hardware_builder/robots/march4.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
# For convenience it is easiest if the joint order is maintained, it is chosen to sort the joints alphabetically.
22
march4:
33
ifName: enp2s0
4-
ecatCycleTime: 4
5-
ecatSlaveTimeout: 50
4+
cycleTime: 4
5+
slaveTimeout: 50
66
joints:
77
- left_ankle:
88
actuationMode: torque

march_hardware_builder/robots/pdb.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
pdb:
22
ifName: enp2s0
3-
ecatCycleTime: 4
3+
cycleTime: 4
44
powerDistributionBoard:
55
slaveIndex: 1
66
bootShutdownOffsets:

march_hardware_builder/robots/test_joint_linear.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
testjoint_linear:
22
ifName: enp2s0
3-
ecatCycleTime: 4
4-
ecatSlaveTimeout: 50
3+
cycleTime: 4
4+
slaveTimeout: 50
55
joints:
66
- linear_joint:
77
actuationMode: torque

march_hardware_builder/robots/test_joint_rotational.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
testsetup:
22
ifName: enp2s0
3-
ecatCycleTime: 4
4-
ecatSlaveTimeout: 50
3+
cycleTime: 4
4+
slaveTimeout: 50
55
joints:
66
- rotational_joint:
77
actuationMode: torque

march_hardware_interface/src/march_hardware_interface_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ int main(int argc, char** argv)
5454
{
5555
try
5656
{
57-
march.waitForPdo();
57+
march.waitForUpdate();
5858

5959
const ros::Time now = ros::Time::now();
6060
ros::Duration elapsed_time = now - last_update_time;

0 commit comments

Comments
 (0)