Skip to content
Merged
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 6 additions & 4 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -178,6 +178,9 @@ controller_interface::return_type DiffDriveController::update(
double & linear_command = command.twist.linear.x;
double & angular_command = command.twist.angular.z;

const auto update_dt = current_time - previous_update_timestamp_;
previous_update_timestamp_ = current_time;

// Apply (possibly new) multipliers:
const auto wheels = wheel_params_;
const double wheel_separation = wheels.separation_multiplier * wheels.separation;
Expand Down Expand Up @@ -218,7 +221,9 @@ controller_interface::return_type DiffDriveController::update(
}
else
{
odometry_.updateFromVelocity(left_feedback_mean, right_feedback_mean, current_time);
odometry_.updateFromVelocity(
left_feedback_mean*update_dt.seconds(), right_feedback_mean*update_dt.seconds(),
current_time);
}
}

Expand Down Expand Up @@ -258,9 +263,6 @@ controller_interface::return_type DiffDriveController::update(
}
}

const auto update_dt = current_time - previous_update_timestamp_;
previous_update_timestamp_ = current_time;

auto & last_command = previous_commands_.back().twist;
auto & second_to_last_command = previous_commands_.front().twist;
limiter_linear_.limit(
Expand Down