@@ -138,8 +138,8 @@ def __init__(self, robot_brain: rosys.hardware.RobotBrain, *,
138
138
self .motor_error = False
139
139
140
140
lizard_code = remove_indentation (f'''
141
- { name } _motor_z = { expander .name + "." if motors_on_expander and expander else "" } ODriveMotor({ can .name } , { z_can_address } { ', 6' if self .odrive_version == 6 else '' } )
142
- { name } _motor_turn = { expander .name + "." if motors_on_expander and expander else "" } ODriveMotor({ can .name } , { turn_can_address } { ', 6' if self .odrive_version == 6 else '' } )
141
+ { name } _motor_z = { expander .name + "." if motors_on_expander and expander else "" } ODriveMotor({ can .name } , { z_can_address } { ', 6' if self .odrive_version == 6 else '' } )
142
+ { name } _motor_turn = { expander .name + "." if motors_on_expander and expander else "" } ODriveMotor({ can .name } , { turn_can_address } { ', 6' if self .odrive_version == 6 else '' } )
143
143
{ name } _motor_z.m_per_tick = { m_per_tick }
144
144
{ name } _motor_turn.m_per_tick = { 1 / 12.52 }
145
145
{ name } _motor_z.limits({ self .speed_limit } , { self .current_limit } )
@@ -158,15 +158,23 @@ def __init__(self, robot_brain: rosys.hardware.RobotBrain, *,
158
158
{ name } _ref_knife_stop.inverted = false
159
159
{ name } _ref_knife_ground = { expander .name + "." if end_stops_on_expander or ref_knife_ground_pin_expander and expander else "" } Input({ ref_knife_ground_pin } )
160
160
{ name } _ref_knife_ground.inverted = true
161
- { name } _z = { expander .name + "." if motors_on_expander and expander else "" } MotorAxis({ name } _motor_z, { name + "_end_bottom" if is_z_reversed else name + "_end_top" } , { name + "_end_top" if is_z_reversed else name + "_end_bottom" } )
162
161
163
- # TODO: remove when lizard issue 66 is fixed. https://github.com/zauberzeug/lizard/issues/66
162
+ # TODO: remove when lizard issue 66 is fixed.
163
+ { name } _end_top.level = 0
164
+ { name } _end_top.active = false
165
+ { name } _end_bottom.level = 0
166
+ { name } _end_bottom.active = false
164
167
{ name } _ref_motor.level = 0
168
+ { name } _ref_motor.active = false
165
169
{ name } _ref_gear.level = 0
170
+ { name } _ref_gear.active = false
166
171
{ name } _ref_knife_stop.level = 0
172
+ { name } _ref_knife_stop.active = false
167
173
{ name } _ref_knife_ground.level = 0
168
174
{ name } _ref_knife_ground.active = false
169
175
176
+ { name } _z = { expander .name + "." if motors_on_expander and expander else "" } MotorAxis({ name } _motor_z, { name + "_end_bottom" if is_z_reversed else name + "_end_top" } , { name + "_end_top" if is_z_reversed else name + "_end_bottom" } )
177
+
170
178
bool { name } _is_referencing = false
171
179
bool { name } _ref_motor_enabled = false
172
180
bool { name } _ref_gear_enabled = false
0 commit comments