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

update usage reporting to use generated values #531

Merged
merged 1 commit into from
Dec 28, 2023
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
4 changes: 2 additions & 2 deletions pathplannerlib-python/pathplannerlib/auto.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
from commands2.command import Command
from commands2.subsystem import Subsystem
from .config import HolonomicPathFollowerConfig, ReplanningConfig
from hal import report
from hal import report, tResourceType


class NamedCommands:
Expand Down Expand Up @@ -474,7 +474,7 @@ def __init__(self, auto_name: str):
self.setName(auto_name)

PathPlannerAuto._instances += 1
report(107, PathPlannerAuto._instances) # TODO: Use resource type when updated
report(tResourceType.kResourceType_PathPlannerAuto.value, PathPlannerAuto._instances)

@staticmethod
def getStartingPoseFromAutoFile(auto_name: str) -> Pose2d:
Expand Down
4 changes: 2 additions & 2 deletions pathplannerlib-python/pathplannerlib/commands.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
from typing import Callable, Tuple, List
from .config import ReplanningConfig, HolonomicPathFollowerConfig
from .pathfinding import Pathfinding
from hal import report
from hal import report, tResourceType


class FollowPathWithEvents(Command):
Expand Down Expand Up @@ -355,7 +355,7 @@ def __init__(self, constraints: PathConstraints, pose_supplier: Callable[[], Pos
self._goalEndState = GoalEndState(goal_end_vel, target_pose.rotation(), True)

PathfindingCommand._instances += 1
report(108, PathfindingCommand._instances) # TODO: Use resource type when updated
report(tResourceType.kResourceType_PathFindingCommand.value, PathfindingCommand._instances)

def initialize(self):
self._currentTrajectory = None
Expand Down
4 changes: 2 additions & 2 deletions pathplannerlib-python/pathplannerlib/path.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
from .geometry_util import decimal_range, cubicLerp, calculateRadius
from .trajectory import PathPlannerTrajectory, State
from wpilib import getDeployDirectory
from hal import report
from hal import report, tResourceType
import os
import json

Expand Down Expand Up @@ -364,7 +364,7 @@ def __init__(self, bezier_points: List[Translation2d], constraints: PathConstrai
self._previewStartingRotation = preview_starting_rotation

PathPlannerPath._instances += 1
report(106, PathPlannerPath._instances) # TODO: Use resource type when updated
report(tResourceType.kResourceType_PathPlannerPath.value, PathPlannerPath._instances)

@staticmethod
def fromPathPoints(path_points: List[PathPoint], constraints: PathConstraints,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.util.PPLibTelemetry;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.Filesystem;
Expand Down Expand Up @@ -41,7 +42,7 @@ public PathPlannerAuto(String autoName) {
PPLibTelemetry.registerHotReloadAuto(autoName, this);

instances++;
HAL.report(107, instances); // TODO: Use tResourceType class when updated
HAL.report(tResourceType.kResourceType_PathPlannerAuto, instances);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import com.pathplanner.lib.util.PPLibTelemetry;
import com.pathplanner.lib.util.PathPlannerLogging;
import com.pathplanner.lib.util.ReplanningConfig;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
Expand Down Expand Up @@ -98,7 +99,7 @@ public PathfindingCommand(
this.replanningConfig = replanningConfig;

instances++;
HAL.report(108, instances); // TODO: Use tResourceType class when updated
HAL.report(tResourceType.kResourceType_PathFindingCommand, instances);
}

/**
Expand Down Expand Up @@ -144,7 +145,7 @@ public PathfindingCommand(
this.replanningConfig = replanningConfig;

instances++;
HAL.report(108, instances); // TODO: Use tResourceType class when updated
HAL.report(tResourceType.kResourceType_PathFindingCommand, instances);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import com.pathplanner.lib.util.GeometryUtil;
import com.pathplanner.lib.util.PPLibTelemetry;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
Expand Down Expand Up @@ -69,7 +70,7 @@ public PathPlannerPath(
precalcValues();

instances++;
HAL.report(106, instances); // TODO: Use tResourceType class when updated
HAL.report(tResourceType.kResourceType_PathPlannerPath, instances);
}

/**
Expand Down Expand Up @@ -156,7 +157,7 @@ private PathPlannerPath(PathConstraints globalConstraints, GoalEndState goalEndS
this.previewStartingRotation = Rotation2d.fromDegrees(0);

instances++;
HAL.report(106, instances); // TODO: Use tResourceType class when updated
HAL.report(tResourceType.kResourceType_PathPlannerPath, instances);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include "pathplanner/lib/util/PPLibTelemetry.h"
#include <frc/Filesystem.h>
#include <wpi/MemoryBuffer.h>
#include <hal/HAL.h>
#include <hal/FRCUsageReporting.h>

using namespace pathplanner;

Expand All @@ -20,7 +20,7 @@ PathPlannerAuto::PathPlannerAuto(std::string autoName) {
SetName(autoName);

m_instances++;
HAL_Report(107, m_instances); // TODO: Use resource type when updated
HAL_Report(HALUsageReporting::kResourceType_PathPlannerAuto, m_instances);
}

std::vector<std::shared_ptr<PathPlannerPath>> PathPlannerAuto::getPathGroupFromAutoFile(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include "pathplanner/lib/pathfinding/Pathfinding.h"
#include "pathplanner/lib/util/GeometryUtil.h"
#include <vector>
#include <hal/HAL.h>
#include <hal/FRCUsageReporting.h>

using namespace pathplanner;

Expand Down Expand Up @@ -48,7 +48,8 @@ PathfindingCommand::PathfindingCommand(
m_goalEndState = GoalEndState(goalEndVel, targetRotation, true);

m_instances++;
HAL_Report(108, m_instances); // TODO: Use resource type when updated
HAL_Report(HALUsageReporting::kResourceType_PathFindingCommand,
m_instances);
}

PathfindingCommand::PathfindingCommand(frc::Pose2d targetPose,
Expand All @@ -68,7 +69,8 @@ PathfindingCommand::PathfindingCommand(frc::Pose2d targetPose,
Pathfinding::ensureInitialized();

m_instances++;
HAL_Report(108, m_instances); // TODO: Use resource type when updated
HAL_Report(HALUsageReporting::kResourceType_PathFindingCommand,
m_instances);
}

void PathfindingCommand::Initialize() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <wpi/MemoryBuffer.h>
#include <limits>
#include <optional>
#include <hal/HAL.h>
#include <hal/FRCUsageReporting.h>

using namespace pathplanner;

Expand All @@ -28,15 +28,15 @@ PathPlannerPath::PathPlannerPath(std::vector<frc::Translation2d> bezierPoints,
precalcValues();

m_instances++;
HAL_Report(106, m_instances); // TODO: Use resource type when updated
HAL_Report(HALUsageReporting::kResourceType_PathPlannerPath, m_instances);
}

PathPlannerPath::PathPlannerPath(PathConstraints constraints,
GoalEndState goalEndState) : m_bezierPoints(), m_rotationTargets(), m_constraintZones(), m_eventMarkers(), m_globalConstraints(
constraints), m_goalEndState(goalEndState), m_reversed(false), m_previewStartingRotation(), m_isChoreoPath(
false), m_choreoTrajectory() {
m_instances++;
HAL_Report(106, m_instances); // TODO: Use resource type when updated
HAL_Report(HALUsageReporting::kResourceType_PathPlannerPath, m_instances);
}

void PathPlannerPath::hotReload(const wpi::json &json) {
Expand Down