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

Fix for SchunkWsgTrajectoryGenerator failing on delta=0 #20828

Merged
merged 1 commit into from
Jan 26, 2024
Merged
Show file tree
Hide file tree
Changes from all 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
5 changes: 5 additions & 0 deletions manipulation/schunk_wsg/schunk_wsg_trajectory_generator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,11 @@ void SchunkWsgTrajectoryGenerator::UpdateTrajectory(

const double direction = (cur_position < target_position) ? 1 : -1;
const double delta = std::abs(target_position - cur_position);
if (delta == 0) {
// Create the constant trajectory.
trajectory_.reset(new trajectories::PiecewisePolynomial<double>(knots[0]));
return;
}

// The trajectory creation code below is, to say the best, a bit
// primitive. I (sam.creasey) would not be surprised if it could
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <gtest/gtest.h>

#include "drake/common/eigen_types.h"
#include "drake/manipulation/schunk_wsg/gen/schunk_wsg_trajectory_generator_state_vector.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/fixed_input_port_value.h"
#include "drake/systems/framework/system_output.h"
Expand Down Expand Up @@ -41,6 +42,29 @@ GTEST_TEST(SchunkWsgTrajectoryGeneratorTest, BasicTest) {
EXPECT_FLOAT_EQ(output->get_vector_data(0)->GetAtIndex(0), expected_target);
}

// Test the specific case when the last command does not match the current
// command but the difference between the measured position and the desired
// position is zero.
GTEST_TEST(SchunkWsgTrajectoryGeneratorTest, DeltaEqualsZero) {
SchunkWsgTrajectoryGenerator dut(1, 0);
auto context = dut.CreateDefaultContext();

SchunkWsgTrajectoryGeneratorStateVector<double> state;
state.set_last_target_position(0.0);
context->SetDiscreteState(state.value());

const double pos = 0.06;
dut.get_desired_position_input_port().FixValue(context.get(), pos);
dut.get_force_limit_input_port().FixValue(context.get(), 40.0);
dut.get_state_input_port().FixValue(context.get(), -pos / 2.0);

systems::Simulator<double> simulator(dut, std::move(context));
simulator.AdvanceTo(0.1);
Eigen::Vector2d target =
dut.get_target_output_port().Eval(simulator.get_context());
EXPECT_EQ(target[0], -pos);
}

} // namespace
} // namespace schunk_wsg
} // namespace manipulation
Expand Down