Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixes three things Hangprinter needs #680

Merged
merged 5 commits into from
May 31, 2022

Conversation

tobbelobb
Copy link
Contributor

... because otherwise, the effect of the callback is canceled by an
assignment in the main update() loop, that calculates input_pos
based on steps_, if we're in step/dir mode.

  • Fixes a steps_ underflow/wrapping bug

tobbelobb added a commit to tobbelobb/hangprinter that referenced this pull request Mar 22, 2022
... follow this pull request to see when stock ODriveFirmware can be
used again.

odriverobotics/ODrive#680
@tobbelobb
Copy link
Contributor Author

tobbelobb commented Mar 22, 2022

For my step/dir usecase to work properly, I set these configuration values:

requested_state = AXIS_STATE_IDLE # or things will explode
steps_per_rotation = 400.0 # or whatever
controller.config.circular_setpoints = False
controller.config.circular_setpoint_range = 10000.0 # This somehow has an effect even if circular_setpoints=False
controller.config.steps_per_circular_range = steps_per_rotation*circular_setpoint_range # This is extremely critical
save_configuration()

The requirement of the "extremely critical" line is kind of mentioned as part of the name of the variable, but it wasn't immediately clear to me either from the docs or from Oskar's heads up yesterday.

It was also very confusing that circular_setpoints and circular_setpoints_range are two separate features. Judging by the names of the variables I had assumed that circular_setpoints_range was a config variable for the feature called circular_setpoints.

@madcowswe
Copy link
Collaborator

madcowswe commented Mar 22, 2022

You said you fixed an underflow bug, but I think that's not right. steps_ should always be positive in the circular range. So if the initial position is slightly negative, and the circular range is 10000, and you have 400 steps per turn, the expected step count should be ~3,999,999 and the input_pos should be ~9,999.99.
If you change this, so steps_ is allowed to take negative numbers, that violates a bunch of assumptions in various places.

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Mar 23, 2022

Ok. Is there a third variable at play here? My motor is able to run both forwards and backwards relative to zero, when driven by step/dir. It doesn't suddenly spin wildly when I step below zero, like my CAN code in this commit did (before I "fixed" the underflow by allowing negative steps_).

I mocked up the steps_ -> input_pos and input_pos -> steps_ functions on my local computer in the office, transforming back and forth two times. I thought pos_wrap might be the third variable that makes the negative positions work, but I wasn't able to confirm it. Since steps_ is of a type that's allowed to go negative, I ended up assuming it should be allowed to go negative. According to your comment, I was wrong.

Any ideas how we avoid the sudden wild spin if Controller::set_input_pos_and_steps(float pos) receives a negative pos value?

@tobbelobb
Copy link
Contributor Author

So the "underflow flix" only appeared to be needed because I had used step/dir together with circular_setpoints = false. Reverting the "underflow fix", fixing my config instead, and this should be ready for testing on hw again.

@tobbelobb
Copy link
Contributor Author

I put curcular_setpoints = true and tried again.
I stepped a few steps forward. That worked as expected.
Then I stepped a few steps backwards, so input_pos wrapped around to 9999.5 (my circular_setpoint_range is 10000).
I expected the motor to make a very small movement.
Instead it started a looooong but slow movement (not full speed, maybe 1 rev/s).

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Apr 5, 2022

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Apr 5, 2022

When I cross below pos_setpoint = 0, then

  • pos_setpoint wraps to 9999.99 (as it should).
  • odrv0.axis0.encoder.pos_estimate grows negative, as motor continues to rotate (as it should since the motor keeps rotating)
  • odrv0.axis0.encoder.pos_circular stays 0 (it should also wrap I think, but I can't get it to wrap down through 0)
  • The motor keeps rotating at a constant speed for ever (it should not rotate, since I'm sending no new step signals)

I tested dropping below the wrap limit at very low motor speed.
After crossing the 0 from above, the motor maintains this low speed for ever, even if I give it no further signals.
This tells me that motor current is calculated from the small difference between where pos_circular is and where it should have been (which is 0.05 rotations in this case).

Sending a few step-signals forward, to get the pos_setpoint back above the wrap limit makes the motor settle, so we get
pos_setpoint = pos_circular = 0.047 again.

@tobbelobb
Copy link
Contributor Author

I'm suspecting that the bug comes from here:
https://github.com/odriverobotics/ODrive/blob/master/Firmware/MotorControl/encoder.cpp#L806
Since it's the only place where pos_circular_ is treated differently than pos_estimate_, which continues to work as intended across the wrap limit.

@tobbelobb
Copy link
Contributor Author

At least, since the speed stays constant, we know that *pos_estimate_circular has not been updated as it should here: https://github.com/odriverobotics/ODrive/blob/master/Firmware/MotorControl/controller.cpp#L255

@tobbelobb
Copy link
Contributor Author

So the 0.5.4 fw indeed has an underflow bug. I'm not able to fix it, so I will go back to 0.5.1 I think.

@tobbelobb
Copy link
Contributor Author

After reducing circular range from 10000 down to 1000 it works as expected across 0.

The setting of input pos via can also seems to work.

However, my application reads out encoder estimate first, and then uses that to set input pos. This doesn't work when we're using circular setpoints. I get an offset between the encoder readout and the setpoint required for the machine to stand completely still upon switching to pos mode.

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Apr 5, 2022

In my opinion the pos_circular variables are all implementation details that should not leak out of the ODrive. So I don't want to read out pos_circular via CAN, and set it back via MSG_SET_INPUT_POS. I don't want to read the linear estimate and convert it to a circular estimate either.

I pushed a suggestion for how my use case may be supported. By making the motor to stand still upon enabling position control via CAN, regardless of what happened before that.

If users depend on the feature that the motor immediately chases some setpoint upon entering position control mode, I'm sure their use case can be supported by setting their desired input pos immediately after enabling position control mode.

It's much safer that way.

@tobbelobb
Copy link
Contributor Author

The latest fw changes have been tested on hardware and seems to work well.

... because otherwise, the effect of the callback is canceled by an
assignment in the main update() loop, that calculates input_pos
based on steps_, if we're in step/dir mode.

- Fixes a steps_ underflow/wrapping bug
@tobbelobb
Copy link
Contributor Author

Rebased, fixed some issues, and force pushed.
See which issues here: https://discord.com/channels/369667319280173067/369678934985408524/961625420451680296

Copying my comments so you get the whole picture:

"Hi, I've made a build of the devel branch, and can't seem to get the motors into closed loop control anymore. dump_errors(odrv0) reports no errors, and the motors do the full calibration sequence just fine
But when I odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL nothing happens
My config worked on the devel branch on March 8 2022, so some of the very recent commits has broken closed loop control
I also got a MOTOR_ERROR_UNKNOWN_PHASE_ESTIMATE error upon fw upgrade that I didn't have before.
Solved by temporarily setting odrv0.axis.motor.config.pre_calibrated = False, and doing the full calibration sequence before setting pre_calibrated back to true.
I did a restore-config which threw the motor I had earlier asked to be in closed loop control, into a wild spin

I got it working again by reverting the commit called "add back subcomponent error flags"
That commit seems to change the behavior around the odrv0.axis0.motor.config.pre_calibrated-setting
First of all, it sets motor.config.pre_calibrated upon restoring an old config, and I get an axis error: UNKNOWN ERROR: 0x00000040 in addition to the motor error: MOTOR_ERROR_UNKNOWN_PHASE_ESTIMATE that I got before the "add back subcomponent error flags"-commit was added.

Before the "add back subcomponent error flags"-commit, I could get my system back to working by doing a full calibration sequence, setting motor -and encoder-pre_calibrated flags to True and rebooting.

After the "add back subcomponent error flags"-commit I can still do the full calibration sequence, and set my pre_calibrated flags, but the system does not get back to working after saving and rebooting. dump_errors reports no errors, but the motors refuse to enter closed loop mode.

Also, after the "Fix get_iq_callbacks function"-commit, the CANSimple::get_iq_callback(axis)-function only sends a response if axis==0.
I get no CAN response for my axis1.

Setting the get_iq_callback() back to the state it was in 0.5.1 gives me my axis1 readings back, most of the time.

bool CANSimple::get_iq_callback(const Axis& axis) {
    can_Message_t txmsg;
    txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
    txmsg.id += MSG_GET_IQ;
    txmsg.isExt = axis.config_.can.is_extended;
    txmsg.len = 8;

    auto& current_control = axis.motor_.current_control_;
    auto [dummy, Idq_setpoint] = current_control.Idq_setpoint_.value();
    float const Iq_measured = current_control.Iq_measured_;

    uint32_t floatBytes;
    static_assert(sizeof(Idq_setpoint) == sizeof(floatBytes));
    std::memcpy(&floatBytes, &Idq_setpoint, sizeof(floatBytes));

    txmsg.buf[0] = floatBytes;
    txmsg.buf[1] = floatBytes >> 8;
    txmsg.buf[2] = floatBytes >> 16;
    txmsg.buf[3] = floatBytes >> 24;

    static_assert(sizeof(floatBytes) == sizeof(Iq_measured));
    std::memcpy(&floatBytes, &Iq_measured, sizeof(floatBytes));
    txmsg.buf[4] = floatBytes;
    txmsg.buf[5] = floatBytes >> 8;
    txmsg.buf[6] = floatBytes >> 16;
    txmsg.buf[7] = floatBytes >> 24;

    return canbus_->send_message(txmsg);
}

The only thing I can see that is different is that this version might be slightly faster.
The fact that it still fails from time to time (ca 1-5% of the time) supports this.
In v0.5.1 it never failed (unsure if that board sends heartbeat messages or not).

I could get rid of the last few failing CAN calls by disabling the heartbeat messages: odrv0.axis0and1.config.can.heartbeat_rate_ms = 0

@samuelsadok
Copy link
Member

I get an axis error: UNKNOWN ERROR: 0x00000040

This corresponds to AXIS_ERROR_MOTOR_FAILED, one of the error flags that was added back. If you run odrivetool from the git repository it should display correctly.

After the "add back subcomponent error flags"-commit I can still do the full calibration sequence, and set my pre_calibrated flags, but the system does not get back to working after saving and rebooting. dump_errors reports no errors, but the motors refuse to enter closed loop mode.

Generally we want to keep this commit but this sounds like a bug. I don't have an absolute encoder setup handy so I cannot easily try. What happens if you run encoder offset calibration after reboot? Does it enter closed loop control after that? Maybe you can also check with the debugger to see where it goes wrong?

I don't really know what's wrong with CAN. Maybe you can swap the node IDs of axis0 and axis1 and see if the dropped messages are still on axis1 or moved to axis0.

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Apr 8, 2022

If you run odrivetool from the git repository it should display correctly.

I was running odrivetool from the git repository.

I don't have an absolute encoder setup handy so I cannot easily try.

I use the 8192 cpr indexed encoder from the ODrive webshop. Not an absolute one.

What happens if you run encoder offset calibration after reboot? Does it enter closed loop control after that?

The problem persists.

Maybe you can also check with the debugger to see where it goes wrong?

Sorry, I don't have time for this now. If you detail how I would do it maybe I get time in the future.

With the can, it's a timing issue. Left unchanged, the axis1 fails (response is too slow, so my other board times out waiting for a response) 100% of the time. If I change the code around slightly, so make it faster, then the problem disappears from axis1, but appears 10% of the time in axis0 instead. If I make the code even faster, the 10% reduces to 5%. If I remove the heartbeat messages, the problem disappears completely.

I tried to provoke the same error using the get_encoder_estimate message but failed. The encoder messages never time out.

@samuelsadok
Copy link
Member

I'll look at your response next week but in the meantime you could try to compile in release mode instead of debug mode, that could free up some CPU time.

@tobbelobb
Copy link
Contributor Author

All my builds have been in release mode

@samuelsadok
Copy link
Member

Can you confirm that this is what you're doing:

  1. Configure and calibrate everything
  2. Save & Reboot
  3. Encoder index search
  4. Closed loop control

And step 4 succeeds before cc7bbd4 and fails after cc7bbd4?

Regarding CAN, it sounds like in both cases the ODrive sends back the correct response, just in one case it's a bit slower so your receiving end times out?

@tobbelobb
Copy link
Contributor Author

Yes, can confirm that step 4 succeeds before cc7bbd4 and fails after.

Regarding CAN, I haven't looked at the signal, or tried extending the Duet3 timeout, so I can't say for sure. But I believe what you describe is what happens.

@samuelsadok
Copy link
Member

I tried the following on the latest devel (daa089c) and it works as expected, the ODrive enters closed loop control in the end. What do I need to change to reproduce the bug?

odrv0.erase_configuration()
odrv0.axis0.requested_state = AXIS_STATE_MOTOR_CALIBRATION
odrv0.axis0.motor.config.pre_calibrated = True
odrv0.axis0.encoder.config.use_index = True
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION
odrv0.axis0.encoder.config.pre_calibrated = True
odrv0.save_configuration()
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH
odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL

Regarding the CAN delay we currently don't make any real-time guarantees for the responses but we can look into that. Do you know by any chance what the timeout of Duet3 is? Note that on ODrive Pro we have much a more generous CPU budget so it should probably not be a problem there.

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Apr 19, 2022

Hi, I'm back, had a few days off.

Do you know by any chance what the timeout of Duet3 is?

It looks like it waits 200 ms. But given the names of the variables, it looks like it has used the wrong variable, so it should really have waited 1000 ms. I'll check if this will get a fix on the Duet side, and if the potential fix would solve the problem.

What do I need to change to reproduce the bug?

I'll try to reproduce the bug with your minimal config.
My current gut feeling is that C-style enums might be giving us undefined behavior, and that we get different behaviors from different compiler versions. Once I've reproduced the bug I'll send the hex file and compiler info over.

@tobbelobb
Copy link
Contributor Author

I made an experiment with the CAN.

  • Duet side was updated to use 1000 ms timeout (up from the 200 ms used before)
  • ODrive ran a build from the daa089c commit

Results were:

  • If I disable heartbeat messages, then I never get timeouts.
  • If I have heartbeats running every 100 ms (the default) on both axes, then I get timeouts ca 1% of the time.

I guess that's good enough for me. I'll make a PR on the Duet side and remove my CAN fixes from this PR.

@tobbelobb
Copy link
Contributor Author

I ran the minimal config example posted above and the motor indeed entered closed loop control.

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Apr 19, 2022

I made an experiment regarding the closed loop state:

odrv0.axis0.requested_state = AXIS_STATE_MOTOR_CALIBRATION
odrv0.axis0.motor.config.pre_calibrated = True
odrv0.axis0.encoder.config.use_index = True
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH
odrv0.axis0.requested_state = AXIS_STATE_ENCODER_OFFSET_CALIBRATION
odrv0.axis0.encoder.config.pre_calibrated = True
odrv0.save_configuration()

After this, the axis0 of the board booted into a working closed loop control as expected.

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Apr 19, 2022

On axis1, after the restore-config and the save_config() I instead did what I would have done before:

odrv0.axis1.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE
odrv0.axis1.encoder.config.pre_calibrated = True
odrv0.axis0.requested_state = AXIS_STATE_IDLE
odrv0.axis1.requested_state = AXIS_STATE_IDLE
odrv0.save_configuration()

The motor on axis1 wakes up after the reboot with odrv0.axis1.motor.config.pre_calibrated == False, and does not enter closed loop control. dump_errors(odrv0) also says AXIS_ERROR_INVALID_STATE.

Suspecting that AXIS_STATE_MOTOR_CALIBRATION is needed, I ran the following:

odrv0.axis1.requested_state = AXIS_STATE_MOTOR_CALIBRATION
odrv0.axis1.motor.config.pre_calibrated = True
odrv0.axis0.requested_state = AXIS_STATE_IDLE
odrv0.axis1.requested_state = AXIS_STATE_IDLE
odrv0.save_configuration()

After this, the motor on axis1 also woke up in a working closed loop mode as expected.

So after commit daa089c, the AXIS_STATE_FULL_CALIBRATION_SEQUENCE and encoder.config.pre_calibrated = True is no longer sufficient after a config restore. We now also have to do AXIS_STATE_MOTOR_CALIBRATION and motor.config.pre_calibrated = True.

Given the name of the full calibration sequence, I'd consider this a bug. Luckily a very easy one to work around, so I'll revert my revert and let you decide instead.

@tobbelobb
Copy link
Contributor Author

I get an axis error: UNKNOWN ERROR: 0x00000040

^That message has not appeared during any of my experiments today.

@tobbelobb
Copy link
Contributor Author

Timeout fix on the Duet side, for reference: Duet3D/RepRapFirmware#568

@tobbelobb
Copy link
Contributor Author

We now also have to do AXIS_STATE_MOTOR_CALIBRATION and motor.config.pre_calibrated = True

I did a third experiment where I dropped the AXIS_STATE_MOTOR_CALIBRATION. So after restore-config and save_config() I did:

odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE
odrv0.axis0.encoder.config.pre_calibrated = True
odrv0.axis0.motor.config.pre_calibrated = True
odrv0.save_configuration()

The axis0 woke up and entered closed loop control as expected. So there's no bug. Just a new variable (motor.config.pre_calibrated) that needs to be explicitly set to True.

I was a bit surprised by this result since I thought I had done exactly this experiment before my vacation. I guess I must have made a typo last time. It's clearly working now at least.

@tobbelobb
Copy link
Contributor Author

I removed the two unnecessary commits (CAN timing fix and enum commit revert) from this PR and force pushed.

I built a new hex with only the three relevant commits included. I tested it on hardware, including jumping back and forth between pos mode and torque mode a few times and jogging a few rotations via step/dir. It works as expected.

@Wetmelon
Copy link
Collaborator

Looks like set_input_pos_and_steps should be the write callback for input_pos to handle it correctly on Fibre?

@tobbelobb
Copy link
Contributor Author

Yeah we probably should have the same behavior for all the protocols. I can't do those hw tests though, so I won't include in this PR. Feel free to add if you have the time (or if you dare to do it without testing on hw).

In case we don't get any voluntary Fibre coders/testers, may we merge my PR anyways, and do the Fibre change when need arises? As I understand it, there's a chance that this firmware's development gets completely sunset before an explicit need arises anyways.

@tobbelobb
Copy link
Contributor Author

Actually, I took 0.5.4 + these three commits out for a full scale print test today. Turns out, the motor wanders about quite a lot (many tens of degrees). It doesn't sit completely still when it's supposed to, and it doesn't return to the same point after jogging it back and forth.

@tobbelobb
Copy link
Contributor Author

Motors are random-waliking about 20 degrees back and at a speed varying from 1 deg/sec to 0.00001 deg/sec. If I send movement commands, the errors get much worse much faster. Up to several hundred degrees+.

I had a similar error before, when ``circular_setpoint_range` was 10000. I've since lowered it to 1000. Should I lower it even more?

@tobbelobb
Copy link
Contributor Author

I did an experiment where I lowered circular_setpoint_range to 100. The random-walk disappeared, and I got fluctuations around zero instead. The fluctuations were +-0.21 degrees, typically ca 0.08. This is larger than the fluctuations I got on the 0.5.1 driven board, which was +-0.10, typically 0.00.

@tobbelobb
Copy link
Contributor Author

I'm not sure I understand what I should put circular_setpoint_range to. @madcowswe told me to put it to a value that encompasses my build volume. That would be 10000, which didn't work. Now I'm down to 1% of that.

Any reason why I wouldn't put it all the way down to 2? (I tried 1, which didn't work)

It seems to carry a trade-off between setpoint range size, and precision. A trade-off I don't really want to have to make.

@tobbelobb
Copy link
Contributor Author

I tried lowering from 100 to 10. I wasn't able to detect any additional accuracy or precision when at 10 compared to when I was at circular_setpoint_range = 100.

@tobbelobb
Copy link
Contributor Author

tobbelobb commented Apr 27, 2022

Today the board is back to drifting those motors. -8 degrees now and still drifting. Gets worse if I step the motors. Also gets worse when motors are under load. That's probably the reason why the problem appeared solved yesterday. There were less pretension on the motors during the later (seemingly working) tests.

@tobbelobb
Copy link
Contributor Author

tobbelobb commented May 2, 2022

Today I did another experiment to see if the drifting problem exists in 0.5.1 as well:

  • Powered my Hangprinter, incl the ODrives
  • Detached belt from motor
  • Rotated the motor 200 turns via odrivetool: odrv0.axis1.controller.input_pos = 200
  • Re-attached belt to motor
  • Homed my Hangprinter like I usually do:
    • Enter Torque mode
    • Small movement to get to the origin. After this, pos_estimate was at 197.13
    • Re-enter position mode. After this, input_pos is also 197.13
  • Checked if drift problem occurs during stationary, static small load, by
    • Reading encoder (linear) estimate via Duet
    • Reading pos_estimate via odrivetool
    • Observing line stiffness

Result: No drift beyond an error margin of +-0.2 degrees.

Since the 0.5.5 drift got worse when I moved the motors, I commanded the Hangprinter to move its effector around. This jogs the motors and varies their load. The result was still the same. No significant drift in 0.5.1.

@tobbelobb
Copy link
Contributor Author

Here's a issue describing the drift bug, which has nothing to do with this PR: #688

@tobbelobb
Copy link
Contributor Author

Having shown that the drift issue is not related to this PR's commits I hope we can merge this PR soon. 😉

.. because circular_setpoints was broken beyond repair.
@tobbelobb tobbelobb changed the title Sets steps_ in CANSimple::set_input_pos_callback Fixes three things Hangprinter needs May 4, 2022
Copy link
Collaborator

@madcowswe madcowswe left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks good in general, thank you. We just need to make the behavior consistent on the other (non-CAN) interfaces. See my other note.

Comment on lines 274 to 283
if (mode == Controller::CONTROL_MODE_POSITION_CONTROL) {
float estimate = 0.0f;
if (axis.controller_.config_.circular_setpoints) {
estimate = axis.encoder_.pos_circular_.any().value_or(0.0f);
} else {
estimate = axis.encoder_.pos_estimate_.any().value_or(0.0f);
}

axis.controller_.set_input_pos_and_steps(estimate);
}
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This reaction on writing the control mode is appropriate, but we need the behavior to be consistent when set from other sources than CAN. My suggestion is:

  1. Merge to a reusable function this snippet with the "// To avoid any transient on startup" section in axis.cpp start_closed_loop_control. You could call it set_setpoint_to_estimate.
  2. Add a c_setter tag to the control_mode endpoint in odrive-interface.yaml, so this can get executed when we write it on USB or UART.
  3. Add an entry in the changelog about this reaction on control mode change.

Defines and uses set_setpoint_to_estimate() reusable function
Uses it in three places:
 - axis.cpp to avoid transient on startup
 - can_simple.cpp to avoid sudden movement upon mode change
 - odrive-interface.yaml just to make it executable via USB and UART

Swaps set_input_pos() to set_input_pos_and_steps() so that we get the
same behavior when changing input_pos over USB and UART as we get when
we change it via CAN.
@tobbelobb
Copy link
Contributor Author

Thanks for the comments.
Since consistent behavior across interfaces is desired, I tried to also change the c_setter of input_pos as well, to match with what the CAN interface currently does.

I have no experience with editing odrive-interface.yaml and took a guess at how it might work.
I tested that it compiles, I did not test it on hardware.
Please review my changes in odrive-interface.yaml carefully.
Preferably test on hardware whether it gives the behavior you wanted.

@madcowswe
Copy link
Collaborator

Hi, you didn't turn on allowing push access to maintainers of destination of the PR so I can't push updates. I made some changes and moved the PR to here:
#689

@tobbelobb
Copy link
Contributor Author

Hi thanks for reviewing, making the change and moving the PR. Didn't know that setting, sorry.

tobbelobb added a commit to tobbelobb/hangprinter that referenced this pull request May 13, 2022
... follow this pull request to see when stock ODriveFirmware can be
used again.

odriverobotics/ODrive#680
@samuelsadok samuelsadok merged commit fa144cf into odriverobotics:devel May 31, 2022
@tobbelobb
Copy link
Contributor Author

This PR was wholly superseded by #689. I suggest reverting the merge of this PR.

@tobbelobb
Copy link
Contributor Author

Never mind my previous comment. Everything's fine, the right commits are on top. No action is needed. Sry for the back-and-forth. I'm super happy about Hangprinter fixes having been merged. Thanks.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants