No matching call to 'frc::SwerveDriveOdometry<4>::SwerveDriveOdometry(<brace-enclosed initalizer list>)

I’ve been running into this error in the 2023 beta version of WPIlib. The error message I am getting is :
No matching call to 'frc::SwerveDriveOdometry<4>::SwerveDriveOdometry(<brace-enclosed initalizer list>)
in reference to this line:
static frc::SwerveDriveOdometry<4> odometry{kinematics, frc::Rotation2d{0_deg}};
Note: kinematics is defined as the following (keep in mind it uses extern):

frc::SwerveDriveKinematics<4> kinematics{frc::Translation2d{9.125_in, -9.125_in},
                                         frc::Translation2d{9.125_in, 9.125_in},
                                         frc::Translation2d{-9.125_in, -9.125_in},
                                         frc::Translation2d{-9.125_in, 9.125_in}};

You’re missing a constructor arg to SwerveDriveOdometry. The kinematics-taking constructor also requires an array of module positions:

SwerveDriveOdometry(
      SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
      const wpi::array<SwerveModulePosition, NumModules>& modulePositions,
      const Pose2d& initialPose = Pose2d{});

I have tried that with this code but I get the same error:

    const static frc::SwerveDriveOdometry<4> odometry{
        Odometry::kinematics,
        Drivetrain::getCCWHeading(),
        module_states,
        frc::Pose2d{5_m, 13.5_m, 0_rad}
        };

Odometry::kinematics is shown above.
Drivetrain::getCCWHeading() is a wrapper around units::degree_t{navx->GetAngle()}
Finally, module_states is defined as:

wpi::array module_states{
    Module::front_left->getState(),
    Module::front_right->getState(),
    Module::back_left->getState(),
    Module::back_right->getState()};

and the getState() function is defined as:

frc::SwerveModuleState SwerveModule::getState()
{
    return {units::meters_per_second_t{(driver.GetSelectedSensorVelocity() / DRIVER_TICKS_PER_WHEEL_RADIAN * WHEEL_RADIUS) / 0.1_s},
            frc::Rotation2d(getAngle())};
}

The modules themselves are unique pointers.

I have also tried passing the getState()s in curly brackets like the docs to no avail.

Could you post a link to your code and the full compilation error? There isn’t enough context here to figure out what’s gone wrong.

If I had to guess based on what you’ve provided, Drivetrain::getCCWHeading() doesn’t return a Rotation2d and using {} for constructing SwerveDriveOdometry means no implicit conversion to Rotation2d occurs.

If navx is an AHRS, you probably want navx->GetRotation2d() there instead.

The key is in the parameter name.

I think you are supplying swerve module states not swerve module position. To me the parameter naming is not great as it’s a bit misleading.

I think this has changed in the 2023 release. Odometry now wants module distances in metres and angles in radians, not module velocities and angles like it used to be.

Sample code from swerve example

I was wrong, Drivetrain::getCCWHeading() is defined as frc::Rotation2d navx->GetAngle()

I think that the issue is a matter of passing SwerveModulePosition (desired) and not SwerveModuleState (Current). I am attempting to create a get_position() method like the example provides, however I am running into some issues. The method is defined as:

frc::SwerveModulePosition SwerveModule::get_position() const {
    return {
        units::meter_t{driver.GetSelectedSensorPosition()},
        units::degree_t{cancoder.GetAbsolutePosition()}
    };
}

However, compilation returns this error:

> Task :compileFrcUserProgramDebugExecutableFrcUserProgramCpp
/src/main/cpp/SwerveModule.cpp: In member function 'frc::SwerveModulePosition SwerveModule::get_position() const':
/src/main/cpp/SwerveModule.cpp:99:56: error: passing 'const ctre::phoenix::motorcontrol::can::WPI_TalonFX' as 'this' argument discards qualifiers [-fpermissive]
   99 |         units::meter_t{driver.GetSelectedSensorPosition()},
      |                        ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~
In file included from .gradle/caches/transforms-3/4a637064885c83a0dfb284ae40cea294/transformed/api-cpp-5.21.4-headers/ctre/phoenix/motorcontrol/can/BaseTalon.h:7,
                 from .gradle/caches/transforms-3/4a637064885c83a0dfb284ae40cea294/transformed/api-cpp-5.21.4-headers/ctre/phoenix/motorcontrol/can/TalonFX.h:7,
                 from .gradle/caches/transforms-3/4a637064885c83a0dfb284ae40cea294/transformed/api-cpp-5.21.4-headers/ctre/Phoenix.h:21,
                 from /src/main/include/SwerveModule.hpp:7,
                 from /src/main/cpp/SwerveModule.cpp:1:
/.gradle/caches/transforms-3/4a637064885c83a0dfb284ae40cea294/transformed/api-cpp-5.21.4-headers/ctre/phoenix/motorcontrol/can/BaseMotorController.h:1119:56: note:   in call to 'virtual double ctre::phoenix::motorcontrol::can::BaseMotorController::GetSelectedSensorPosition(int)'
 1119 |                                         virtual double GetSelectedSensorPosition(int pidIdx = 0);
      |                                                        ^~~~~~~~~~~~~~~~~~~~~~~~~
/src/main/cpp/SwerveModule.cpp:100:53: error: passing 'const ctre::phoenix::sensors::WPI_CANCoder' as 'this' argument discards qualifiers [-fpermissive]
  100 |         units::degree_t{cancoder.GetAbsolutePosition()}
      |                         ~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~
/.gradle/caches/transforms-3/4a637064885c83a0dfb284ae40cea294/transformed/api-cpp-5.21.4-headers/ctre/phoenix/motorcontrol/IMotorController.h:18,
                 /.gradle/caches/transforms-3/4a637064885c83a0dfb284ae40cea294/transformed/api-cpp-5.21.4-headers/ctre/phoenix/motorcontrol/can/BaseMotorController.h:6:
.gradle/caches/transforms-3/4a637064885c83a0dfb284ae40cea294/transformed/api-cpp-5.21.4-headers/ctre/phoenix/sensors/CANCoder.h:221:40: note:   in call to 'double ctre::phoenix::sensors::CANCoder::GetAbsolutePosition()'
  221 |                                 double GetAbsolutePosition();
      |                                        ^~~~~~~~~~~~~~~~~~~

Source code, I can’t give you the compiler error since I made revisions and forget what they were

That error about discarding qualifiers means GetSelectedSensorPosition() wasn’t const-qualified, so you can’t call it within a const-qualified function: CTRE Phoenix C++: ctre::phoenix::motorcontrol::can::BaseMotorController Class Reference

You can fix it by not making your get_position() function const-qualified (i.e., remove the const suffix from the function signature).

That worked, thanks for the help

This topic was automatically closed 365 days after the last reply. New replies are no longer allowed.