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

Temporarily set talon to disabled before giving a new setpoint in motionmagic mode #74

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
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
Binary file added jetson_setup/gs_usb.ko.4.4.38-tegra-patched
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -2174,6 +2174,15 @@ void FRCRobotHWInterface::write(ros::Duration &elapsed_time)
ts.setDemand1Type(demand1_type_internal);
ts.setDemand1Value(demand1_value);

// I think motionmagic calculates a path from currrent setpoint to new setpoint
// If we didn't actually make it to the previous setpoint, this will cause
// problems with random accumulating error. It looks like going from disabled
// back to motionmagic causes the talon to path from current encoder value
// to new setpoint. Temporarily disable the talon before sending a new setpoint
// in motionmagic mode to trigger this behavior.
if (b2 && (in_mode == hardware_interface::TalonMode_MotionMagic))
talon->Set(ctre::phoenix::motorcontrol::ControlMode::Disabled,
command, demand1_type_phoenix, demand1_value);
talon->Set(out_mode, command, demand1_type_phoenix, demand1_value);
}
}
Expand Down