WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
BatterySim.hpp
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 <algorithm>
8#include <numeric>
9#include <span>
10
11#include "wpi/units/current.hpp"
12#include "wpi/units/impedance.hpp"
13#include "wpi/units/voltage.hpp"
14
15namespace wpi::sim {
16
17/**
18 * A utility class to simulate the robot battery.
19 */
21 public:
22 /**
23 * Calculate the loaded battery voltage. Use this with
24 * RoboRioSim::SetVInVoltage(double) to set the simulated battery voltage,
25 * which can then be retrieved with the RobotController::GetBatteryVoltage()
26 * method.
27 *
28 * @param nominalVoltage The nominal battery voltage. Usually 12v.
29 * @param resistance The forward resistance of the battery. Most batteries
30 * are at or below 20 milliohms.
31 * @param currents The currents drawn from the battery.
32 * @return The battery's voltage under load.
33 */
34 static wpi::units::volt_t Calculate(
35 wpi::units::volt_t nominalVoltage, wpi::units::ohm_t resistance,
36 std::span<const wpi::units::ampere_t> currents) {
37 return std::max(0_V, nominalVoltage - std::accumulate(currents.begin(),
38 currents.end(), 0_A) *
39 resistance);
40 }
41
42 /**
43 * Calculate the loaded battery voltage. Use this with
44 * RoboRioSim::SetVInVoltage(double) to set the simulated battery voltage,
45 * which can then be retrieved with the RobotController::GetBatteryVoltage()
46 * method.
47 *
48 * @param nominalVoltage The nominal battery voltage. Usually 12v.
49 * @param resistance The forward resistance of the battery. Most batteries
50 * are at or below 20 milliohms.
51 * @param currents The currents drawn from the battery.
52 * @return The battery's voltage under load.
53 */
54 static wpi::units::volt_t Calculate(
55 wpi::units::volt_t nominalVoltage, wpi::units::ohm_t resistance,
56 std::initializer_list<wpi::units::ampere_t> currents) {
57 return std::max(0_V, nominalVoltage - std::accumulate(currents.begin(),
58 currents.end(), 0_A) *
59 resistance);
60 }
61
62 /**
63 * Calculate the loaded battery voltage. Use this with
64 * RoboRioSimSetVInVoltage(double) to set the simulated battery voltage, which
65 * can then be retrieved with the RobotController::GetBatteryVoltage() method.
66 * This function assumes a nominal voltage of 12V and a resistance of 20
67 * milliohms (0.020 ohms).
68 *
69 * @param currents The currents drawn from the battery.
70 * @return The battery's voltage under load.
71 */
72 static wpi::units::volt_t Calculate(
73 std::span<const wpi::units::ampere_t> currents) {
74 return Calculate(12_V, 0.02_Ohm, currents);
75 }
76
77 /**
78 * Calculate the loaded battery voltage. Use this with
79 * RoboRioSimSetVInVoltage(double) to set the simulated battery voltage, which
80 * can then be retrieved with the RobotController::GetBatteryVoltage() method.
81 * This function assumes a nominal voltage of 12V and a resistance of 20
82 * milliohms (0.020 ohms).
83 *
84 * @param currents The currents drawn from the battery.
85 * @return The battery's voltage under load.
86 */
87 static wpi::units::volt_t Calculate(
88 std::initializer_list<wpi::units::ampere_t> currents) {
89 return Calculate(12_V, 0.02_Ohm, currents);
90 }
91};
92
93} // namespace wpi::sim
A utility class to simulate the robot battery.
Definition BatterySim.hpp:20
static wpi::units::volt_t Calculate(std::span< const wpi::units::ampere_t > currents)
Calculate the loaded battery voltage.
Definition BatterySim.hpp:72
static wpi::units::volt_t Calculate(wpi::units::volt_t nominalVoltage, wpi::units::ohm_t resistance, std::initializer_list< wpi::units::ampere_t > currents)
Calculate the loaded battery voltage.
Definition BatterySim.hpp:54
static wpi::units::volt_t Calculate(std::initializer_list< wpi::units::ampere_t > currents)
Calculate the loaded battery voltage.
Definition BatterySim.hpp:87
static wpi::units::volt_t Calculate(wpi::units::volt_t nominalVoltage, wpi::units::ohm_t resistance, std::span< const wpi::units::ampere_t > currents)
Calculate the loaded battery voltage.
Definition BatterySim.hpp:34
Definition CTREPCMSim.hpp:13