I’m following the WpiLib docs to implement path planning. As I’m creating my example trajectory, I get this build error saying “C:\Users\18082\Desktop\3721Command\3721Command\build\objs\frcUserProgram\release\frcUserProgramCpp\45vqxio4pi9nbs4dcvmcpqo1r\RobotContainer.o: in function RobotContainer::GetAutonomousCommand()': RobotContainer.cpp:(.text+0xd30): undefined reference to
DriveConstants::KDriveKinematics’
collect2.exe: error: ld returned 1 exit status”
I see that my KDriveKinematics variable is located in my constants file under the DriveConstants namespace, but is there something I’m not seeing?
Robot Container File
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "RobotContainer.h"
#include <utility>
#include <frc2/command/button/Trigger.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/RamseteController.h>
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc/trajectory/Trajectory.h>
#include <frc/trajectory/TrajectoryGenerator.h>
#include <frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h>
#include <frc2/command/Commands.h>
#include <frc2/command/RamseteCommand.h>
#include <frc2/command/button/JoystickButton.h>
#include "commands/Autos.h"
//#include "commands/ExampleCommand.h"
#include "commands/Teleop.h"
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Configure the button bindings
ConfigureBindings();
pchsDrive.SetDefaultCommand(Teleop(
&pchsDrive, [this] {return -m_driverController.GetLeftY();},
[this] {return m_driverController.GetRightX();}));
}
void RobotContainer::ConfigureBindings() {
}
frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
// An example command will be run in autonomous
frc::DifferentialDriveVoltageConstraint autoVoltageConstraint{
frc::SimpleMotorFeedforward<units::meters>{
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka},
DriveConstants::KDriveKinematics, 10_V};
frc::TrajectoryConfig config{DriveConstants::kMaxSpeed,
DriveConstants::kMaxAccl};
// Add kinematics
config.SetKinematics(DriveConstants::KDriveKinematics);
// Apply the voltage constraint
config.AddConstraint(autoVoltageConstraint);
// An example trajectory
auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
// Start at the origin facing the +X direction
frc::Pose2d{0_m, 0_m, 0_deg},
// Pass through these two interior waypoints, making an 's' curve path
{frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
// End 3 meters straight ahead of where we started, facing forward
frc::Pose2d{3_m, 0_m, 0_deg},
// Pass the config
config);
frc2::CommandPtr ramseteCommand{frc2::RamseteCommand(
exampleTrajectory, [this] { return pchsDrive.GetPose(); },
frc::RamseteController{DriveConstants::kRamseteB,
DriveConstants::kRamseteZeta},
frc::SimpleMotorFeedforward<units::meters>{
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka},
DriveConstants::KDriveKinematics,
[this] { return pchsDrive.GetWheelSpeeds(); },
frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
[this](auto left, auto right) { pchsDrive.TankDriveVolts(left, right); },
{&pchsDrive})};
// Reset odometry to the starting pose of the trajectory.
pchsDrive.ResetOdometry(exampleTrajectory.InitialPose());
return std::move(ramseteCommand)
.BeforeStarting(
frc2::cmd::RunOnce([this] { pchsDrive.TankDriveVolts(0_V, 0_V); }, {}));
}
Constants File
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include <frc/kinematics/DifferentialDriveKinematics.h>
#include <frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h>
#include <units/acceleration.h>
#include <units/angle.h>
#include <units/length.h>
#include <units/time.h>
#include <units/velocity.h>
#include <units/voltage.h>
#include <numbers>
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or boolean constants. This should not be used for any other
* purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace DriveConstants{
constexpr int RgtFPort = 6;
constexpr int RgtBPort = 7;
constexpr int LftFPort = 4;
constexpr int LftBPort = 5;
constexpr int kLeftMotor1Port = 0;
constexpr int kLeftMotor2Port = 1;
constexpr int kRightMotor1Port = 2;
constexpr int kRightMotor2Port = 3;
constexpr int kLeftEncoderPorts[]{0, 1};
constexpr int kRightEncoderPorts[]{2, 3};
constexpr bool kLeftEncoderReversed = false;
constexpr bool kRightEncoderReversed = true;
//-----------------------------
//Characterization Values (Change later)
//-----------------------------
constexpr auto ks = 0.22_V;
constexpr auto kv = 1.98 * 1_V * 1_s / 1_m;
constexpr auto ka = 0.2 * 1_V * 1_s * 1_s / 1_m;
constexpr double kPDriveVel = 8.5;
//----------------------------------
//Drive Kinematics
//---------------------------------
constexpr auto kTrackwidth = 0.69_m;
extern const frc::DifferentialDriveKinematics KDriveKinematics;
//---------------------------------
// Max Vel / Accl
//----------------------------------
constexpr auto kMaxSpeed = 3_mps;
constexpr auto kMaxAccl = 1_mps_sq;
//----------------------------------
//Ramsete Param
//-----------------------------------
constexpr auto kRamseteB = 2.0 * 1_rad * 1_rad / (1_m * 1_m);
constexpr auto kRamseteZeta = 0.7 / 1_rad;
constexpr int kEncoderCPR = 1024;
constexpr units::meter_t kWheelDiameter = 6_in; //Adjust later
constexpr auto kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameter * std::numbers::pi) / static_cast<double>(kEncoderCPR);
}
namespace OperatorConstants {
constexpr int kDriverControllerPort = 0;
} // namespace OperatorConstants