Skip to content

Commit 5d4c32b

Browse files
author
Monitor March
committed
push for druif
1 parent d410d7a commit 5d4c32b

File tree

7 files changed

+38
-35
lines changed

7 files changed

+38
-35
lines changed

log_lower.mtb

798 KB
Binary file not shown.

ros2/src/hardware/interface/march_hardware/include/march_hardware/motor_controller/odrive/odrive.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ class ODrive : public MotorController {
7878
float getOdriveTemperature();
7979

8080
double getTorqueLimit() const override;
81-
static constexpr double TORQUE_LIMIT = 30.0; // TODO: Determine a better value here
81+
static constexpr double TORQUE_LIMIT = 50.0; // TODO: Determine a better value here
8282

8383
protected:
8484
// Override protected functions from MotorController class

ros2/src/hardware/interface/march_hardware_builder/robots/march7.yaml

+8-8
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ march7:
3131
transmission: 204
3232
direction: 1
3333
torqueSensor:
34-
maxTorque: 10
34+
maxTorque: 50
3535
pids:
3636
position:
3737
p: 30.0
@@ -66,7 +66,7 @@ march7:
6666
transmission: 314
6767
direction: 1
6868
torqueSensor:
69-
maxTorque: 10
69+
maxTorque: 50
7070
pids:
7171
position:
7272
p: 35.0
@@ -101,7 +101,7 @@ march7:
101101
resolution: 12
102102
transmission: 121
103103
torqueSensor:
104-
maxTorque: 10
104+
maxTorque: 50
105105
pids:
106106
position:
107107
p: 25.0
@@ -136,7 +136,7 @@ march7:
136136
resolution: 12
137137
transmission: 121
138138
torqueSensor:
139-
maxTorque: 10
139+
maxTorque: 50
140140
pids:
141141
position:
142142
p: 20.0
@@ -171,7 +171,7 @@ march7:
171171
transmission: 204
172172
direction: 1
173173
torqueSensor:
174-
maxTorque: 10
174+
maxTorque: 50
175175
pids:
176176
position:
177177
p: 30.0
@@ -206,7 +206,7 @@ march7:
206206
transmission: 314
207207
direction: 1
208208
torqueSensor:
209-
maxTorque: 10
209+
maxTorque: 50
210210
pids:
211211
position:
212212
p: 35.0
@@ -241,7 +241,7 @@ march7:
241241
resolution: 12
242242
transmission: 121
243243
torqueSensor:
244-
maxTorque: 10
244+
maxTorque: 50
245245
pids:
246246
position:
247247
p: 25.0
@@ -277,7 +277,7 @@ march7:
277277
resolution: 12
278278
transmission: 121
279279
torqueSensor:
280-
maxTorque: 10
280+
maxTorque: 50
281281
pids:
282282
position:
283283
p: 10.0

ros2/src/hardware/interface/march_hardware_builder/robots/march8.yaml

+24-24
Original file line numberDiff line numberDiff line change
@@ -16,19 +16,19 @@ march8:
1616
absoluteEncoder:
1717
resolution: 14
1818
direction: 1
19-
minPositionIU: 4049 # Ros kills itself if it is in its hard limits (same as encode limits).
20-
maxPositionIU: 5801 # Ros kills itself if it is in its hard limits (same as encode limits).
21-
zeroPositionIU: 5345
22-
lowerSoftLimitMarginRad: 0.00349066 # Ros warns if it is x away from hard limit.
19+
minPositionIU: 4669 # Ros kills itself if it is in its hard limits (same as encode limits).
20+
maxPositionIU: 6474 # Ros kills itself if it is in its hard limits (same as encode limits).
21+
zeroPositionIU: 6019
22+
lowerSoftLimitMarginRad: 0.0349066 # Ros warns if it is x away from hard limit.
2323
upperSoftLimitMarginRad: 0.00349066 # Ros warns if it is x away from hard limit.
24-
lowerErrorSoftLimitMarginRad: 0.00174533 # Ros stops if it is x away from hard limit.
24+
lowerErrorSoftLimitMarginRad: 0.0174533 # Ros stops if it is x away from hard limit.
2525
upperErrorSoftLimitMarginRad: 0.00174533 # Ros stops if it is x away from hard limit.
2626
incrementalEncoder:
2727
resolution: 13
2828
transmission: 204
2929
direction: 1
3030
torqueSensor:
31-
maxTorque: 10
31+
maxTorque: 50
3232
pids:
3333
position:
3434
p: 30.0
@@ -63,12 +63,12 @@ march8:
6363
transmission: 314
6464
direction: 1
6565
torqueSensor:
66-
maxTorque: 10
66+
maxTorque: 50
6767
pids:
6868
position:
69-
p: 10.0
69+
p: 35.0
7070
i: 0.0
71-
d: 0.2
71+
d: 0.6
7272
torque:
7373
p: 0.0
7474
i: 0.0
@@ -98,7 +98,7 @@ march8:
9898
resolution: 12
9999
transmission: 121
100100
torqueSensor:
101-
maxTorque: 10
101+
maxTorque: 50
102102
pids:
103103
position:
104104
p: 25.0
@@ -133,7 +133,7 @@ march8:
133133
resolution: 12
134134
transmission: 121
135135
torqueSensor:
136-
maxTorque: 10
136+
maxTorque: 50
137137
pids:
138138
position:
139139
p: 20.0
@@ -156,19 +156,19 @@ march8:
156156
absoluteEncoder:
157157
resolution: 14
158158
direction: 1
159-
minPositionIU: 1145 # Ros kills itself if it is in its hard limits (same as encode limits).
160-
maxPositionIU: 2891 # Ros kills itself if it is in its hard limits (same as encode limits).
161-
zeroPositionIU: 2435 #9205
162-
lowerSoftLimitMarginRad: 0.00349066 # Ros warns if it is x away from hard limit.
159+
minPositionIU: 1126 # Ros kills itself if it is in its hard limits (same as encode limits).
160+
maxPositionIU: 2915 # Ros kills itself if it is in its hard limits (same as encode limits).
161+
zeroPositionIU: 2460 #9205
162+
lowerSoftLimitMarginRad: 0.0349066 # Ros warns if it is x away from hard limit.
163163
upperSoftLimitMarginRad: 0.00349066 # Ros warns if it is x away from hard limit.
164-
lowerErrorSoftLimitMarginRad: 0.00174533 # Ros stops if it is x away from hard limit.
164+
lowerErrorSoftLimitMarginRad: 0.0174533 # Ros stops if it is x away from hard limit.
165165
upperErrorSoftLimitMarginRad: 0.00174533 # Ros stops if it is x away from hard limit.
166166
incrementalEncoder:
167167
resolution: 13
168168
transmission: 204
169169
direction: 1
170170
torqueSensor:
171-
maxTorque: 10
171+
maxTorque: 50
172172
pids:
173173
position:
174174
p: 30.0
@@ -203,12 +203,12 @@ march8:
203203
transmission: 314
204204
direction: 1
205205
torqueSensor:
206-
maxTorque: 10
206+
maxTorque: 50
207207
pids:
208208
position:
209-
p: 10.0
209+
p: 35.0
210210
i: 0.0
211-
d: 0.2
211+
d: 0.6
212212
torque:
213213
p: 0.0
214214
i: 0.0
@@ -238,7 +238,7 @@ march8:
238238
resolution: 12
239239
transmission: 121
240240
torqueSensor:
241-
maxTorque: 10
241+
maxTorque: 50
242242
pids:
243243
position:
244244
p: 25.0
@@ -274,12 +274,12 @@ march8:
274274
resolution: 12
275275
transmission: 121
276276
torqueSensor:
277-
maxTorque: 10
277+
maxTorque: 50
278278
pids:
279279
position:
280-
p: 15.0
280+
p: 10.0
281281
i: 0.0
282-
d: 2.0
282+
d: 1.5
283283
torque:
284284
p: 0.0
285285
i: 0.0

ros2/src/hardware/interface/march_hardware_interface/include/march_hardware_interface/march_exo_system_interface.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ struct JointInfo {
9191
// RCLCPP_INFO(this->get_logger(), "Weights are in from fuzzy node: position %f, torque %f", msg->position_weight, msg->torque_weight);
9292
// return;
9393
#endif
94-
RCLCPP_INFO(this->get_logger(), "Ignoring calculated weight: position %f, torque %f", msg->position_weight, msg->torque_weight);
94+
// RCLCPP_INFO(this->get_logger(), "Ignoring calculated weight: position %f, torque %f", msg->position_weight, msg->torque_weight);
9595
// setJointsWeight(msg->leg, msg->position_weight, msg->torque_weight);
9696
}
9797

ros2/src/hardware/interface/march_hardware_interface/src/march_exo_system_interface.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -287,6 +287,9 @@ hardware_interface::return_type MarchExoSystemInterface::start()
287287
// jointInfo.position_weight = 0.0f;
288288
// }
289289

290+
RCLCPP_INFO_ONCE((*logger_), "The fuzzy target values are as follows: \n target position: %f \n measured position: %f \n position weight: %f \n target torque: %f \n measured torque: %f \n torque weight: %f",
291+
jointInfo.target_position, jointInfo.position, jointInfo.position_weight, jointInfo.target_torque, jointInfo.torque, jointInfo.torque_weight);
292+
290293
jointInfo.joint.actuate(jointInfo.target_position, jointInfo.target_torque, jointInfo.position_weight, jointInfo.torque_weight);
291294

292295
// Set the first target as the current position

ros2/src/libraries/labrob_qpsolvers

Submodule labrob_qpsolvers updated from edc6b9b to 01ecec2

0 commit comments

Comments
 (0)