Skip to content

Commit

Permalink
Sets steps_ in CANSimple::set_input_pos_callback
Browse files Browse the repository at this point in the history
... 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
  • Loading branch information
tobbelobb committed Apr 7, 2022
1 parent daa089c commit ae262e4
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 4 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ Please add a note of your changes below this heading if you make a Pull Request.
* Ensure endstops update before being checked for errors, to prevent [#625](https://github.com/odriverobotics/ODrive/issues/625)
* Reset trajectory_done_ during homing to ensure a new trajectory is actually computed [#634](https://github.com/odriverobotics/ODrive/issues/634)
* Use `input_xxx` as a DC offset in tuning mode
* Syncs `steps_` with input pos when set explicitly via CAN.

# Releases
## [0.5.4] - 2021-10-12
Expand Down
4 changes: 1 addition & 3 deletions Firmware/MotorControl/axis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,9 +295,7 @@ bool Axis::start_closed_loop_control() {
return false;
} else {
controller_.pos_setpoint_ = *pos_init;
controller_.input_pos_ = *pos_init;
float range = controller_.config_.circular_setpoint_range;
steps_ = (int64_t)(fmodf_pos(*pos_init, range) / range * controller_.config_.steps_per_circular_range);
controller_.set_input_pos_and_steps(*pos_init);
}
}
controller_.input_pos_updated();
Expand Down
6 changes: 6 additions & 0 deletions Firmware/MotorControl/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,12 @@ bool Controller::anticogging_calibration(float pos_estimate, float vel_estimate)
}
}

void Controller::set_input_pos_and_steps(float const pos) {
input_pos_ = pos;
float const range = config_.circular_setpoint_range;
axis_->steps_ = (int64_t)(wrap_pm(pos, range) / range * config_.steps_per_circular_range);
}

void Controller::update_filter_gains() {
float bandwidth = std::min(config_.input_filter_bandwidth, 0.25f * current_meas_hz);
input_filter_ki_ = 2.0f * bandwidth; // basic conversion to discrete time
Expand Down
2 changes: 2 additions & 0 deletions Firmware/MotorControl/controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,8 @@ class Controller : public ODriveIntf::ControllerIntf {
void start_anticogging_calibration();
bool anticogging_calibration(float pos_estimate, float vel_estimate);

void set_input_pos_and_steps(float pos);

void update_filter_gains();
bool update();

Expand Down
2 changes: 1 addition & 1 deletion Firmware/communication/can/can_simple.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,7 @@ bool CANSimple::get_encoder_count_callback(const Axis& axis) {
}

void CANSimple::set_input_pos_callback(Axis& axis, const can_Message_t& msg) {
axis.controller_.input_pos_ = can_getSignal<float>(msg, 0, 32, true);
axis.controller_.set_input_pos_and_steps(can_getSignal<float>(msg, 0, 32, true));
axis.controller_.input_vel_ = can_getSignal<int16_t>(msg, 32, 16, true, 0.001f, 0);
axis.controller_.input_torque_ = can_getSignal<int16_t>(msg, 48, 16, true, 0.001f, 0);
axis.controller_.input_pos_updated();
Expand Down

0 comments on commit ae262e4

Please sign in to comment.