WPILibC++ 2024.3.2
BatterySim.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <numeric>
8#include <span>
9
10#include <units/current.h>
11#include <units/impedance.h>
12#include <units/voltage.h>
13
14namespace frc::sim {
15
16/**
17 * A utility class to simulate the robot battery.
18 */
20 public:
21 /**
22 * Calculate the loaded battery voltage. Use this with
23 * RoboRioSim::SetVInVoltage(double) to set the simulated battery voltage,
24 * which can then be retrieved with the RobotController::GetBatteryVoltage()
25 * method.
26 *
27 * @param nominalVoltage The nominal battery voltage. Usually 12v.
28 * @param resistance The forward resistance of the battery. Most batteries
29 * are at or below 20 milliohms.
30 * @param currents The currents drawn from the battery.
31 * @return The battery's voltage under load.
32 */
33 static units::volt_t Calculate(units::volt_t nominalVoltage,
34 units::ohm_t resistance,
35 std::span<const units::ampere_t> currents) {
36 return nominalVoltage -
37 std::accumulate(currents.begin(), currents.end(), 0_A) * resistance;
38 }
39
40 /**
41 * Calculate the loaded battery voltage. Use this with
42 * RoboRioSim::SetVInVoltage(double) to set the simulated battery voltage,
43 * which can then be retrieved with the RobotController::GetBatteryVoltage()
44 * method.
45 *
46 * @param nominalVoltage The nominal battery voltage. Usually 12v.
47 * @param resistance The forward resistance of the battery. Most batteries
48 * are at or below 20 milliohms.
49 * @param currents The currents drawn from the battery.
50 * @return The battery's voltage under load.
51 */
52 static units::volt_t Calculate(
53 units::volt_t nominalVoltage, units::ohm_t resistance,
54 std::initializer_list<units::ampere_t> currents) {
55 return nominalVoltage -
56 std::accumulate(currents.begin(), currents.end(), 0_A) * resistance;
57 }
58
59 /**
60 * Calculate the loaded battery voltage. Use this with
61 * RoboRioSimSetVInVoltage(double) to set the simulated battery voltage, which
62 * can then be retrieved with the RobotController::GetBatteryVoltage() method.
63 * This function assumes a nominal voltage of 12V and a resistance of 20
64 * milliohms (0.020 ohms).
65 *
66 * @param currents The currents drawn from the battery.
67 * @return The battery's voltage under load.
68 */
69 static units::volt_t Calculate(std::span<const units::ampere_t> currents) {
70 return Calculate(12_V, 0.02_Ohm, currents);
71 }
72
73 /**
74 * Calculate the loaded battery voltage. Use this with
75 * RoboRioSimSetVInVoltage(double) to set the simulated battery voltage, which
76 * can then be retrieved with the RobotController::GetBatteryVoltage() method.
77 * This function assumes a nominal voltage of 12V and a resistance of 20
78 * milliohms (0.020 ohms).
79 *
80 * @param currents The currents drawn from the battery.
81 * @return The battery's voltage under load.
82 */
83 static units::volt_t Calculate(
84 std::initializer_list<units::ampere_t> currents) {
85 return Calculate(12_V, 0.02_Ohm, currents);
86 }
87};
88
89} // namespace frc::sim
A utility class to simulate the robot battery.
Definition: BatterySim.h:19
static units::volt_t Calculate(units::volt_t nominalVoltage, units::ohm_t resistance, std::initializer_list< units::ampere_t > currents)
Calculate the loaded battery voltage.
Definition: BatterySim.h:52
static units::volt_t Calculate(std::initializer_list< units::ampere_t > currents)
Calculate the loaded battery voltage.
Definition: BatterySim.h:83
static units::volt_t Calculate(units::volt_t nominalVoltage, units::ohm_t resistance, std::span< const units::ampere_t > currents)
Calculate the loaded battery voltage.
Definition: BatterySim.h:33
static units::volt_t Calculate(std::span< const units::ampere_t > currents)
Calculate the loaded battery voltage.
Definition: BatterySim.h:69
Definition: XboxControllerSim.h:13