CTRE Phoenix Pro C++ 23.0.12
TalonFX.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
11
12#include "frc/MotorSafety.h"
13#include "frc/motorcontrol/MotorController.h"
14#include "wpi/sendable/Sendable.h"
15#include "wpi/sendable/SendableBuilder.h"
16#include "wpi/sendable/SendableHelper.h"
17#include <hal/SimDevice.h>
18
19#include <string>
20
21namespace ctre {
22namespace phoenixpro {
23namespace hardware {
24
25/**
26 * Class description for the Talon FX integrated motor controller that runs on
27 * associated Falcon motors.
28 *
29 * This must be constructed after main executes. We recommend constructing inside
30 * the robot class or your subsystem classes. Otherwise WPILib motor safety may
31 * produce erroneous behavior.
32 */
34 public frc::MotorController,
35 public frc::MotorSafety,
36 public wpi::Sendable,
37 public wpi::SendableHelper<TalonFX>
38{
39 /**
40 * The StatusSignalValue getters are copies so that calls
41 * to the WPI interface do not update any references
42 *
43 * These are also mutable so the const getter methods are
44 * properly managed.
45 */
47
48 controls::DutyCycleOut m_setterControl{0.0};
49 controls::NeutralOut m_brakeRef{};
50 controls::VoltageOut m_voltageControl{0_V};
51
52 std::string m_description;
53
54 static constexpr phoenix::platform::DeviceType kSimDeviceType = phoenix::platform::DeviceType::PRO_TalonFXType;
55
56 hal::SimDevice m_simMotor;
57 hal::SimDouble m_simSupplyVoltage;
58 hal::SimDouble m_simDutyCycle;
59 hal::SimDouble m_simMotorVoltage;
60 hal::SimDouble m_simTorqueCurrent;
61 hal::SimDouble m_simSupplyCurrent;
62
63 hal::SimDevice m_simForwardLimit;
64 hal::SimBoolean m_simForwardLimitValue;
65
66 hal::SimDevice m_simReverseLimit;
67 hal::SimBoolean m_simReverseLimitValue;
68
69 hal::SimDevice m_simRotor;
70 hal::SimDouble m_simRotorPos;
71 hal::SimDouble m_simRotorRawPos;
72 hal::SimDouble m_simRotorVel;
73
74 int32_t m_simPeriodicUid{-1};
75 std::vector<int32_t> m_simValueChangedUids;
76
77 static void OnValueChanged(const char* name, void *param, HAL_SimValueHandle handle,
78 HAL_Bool readonly, const struct HAL_Value* value);
79 static void OnPeriodic(void* param);
80
81public:
82 /**
83 * Constructs a new Talon FX motor controller object.
84 *
85 * This must be constructed after main executes. We recommend constructing inside
86 * the robot class or your subsystem classes. Otherwise WPILib motor safety may
87 * produce erroneous behavior.
88 *
89 * \param deviceId ID of the device, as configured in Phoenix Tuner.
90 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
91 * - "rio" for the native roboRIO CAN bus
92 * - CANivore name or serial number
93 * - SocketCAN interface (non-FRC Linux only)
94 * - "*" for any CANivore seen by the program
95 * - empty string (default) to select the default for the system:
96 * - "rio" on roboRIO
97 * - "can0" on Linux
98 * - "*" on Windows
99 */
100 TalonFX(int deviceId, std::string canbus = "");
102
103 /**
104 * Common interface for setting the speed of a motor controller.
105 *
106 * \param speed The speed to set. Value should be between -1.0 and 1.0.
107 */
108 void Set(double speed) override;
109 /**
110 * Common interface for seting the direct voltage output of a motor controller.
111 *
112 * \param volts The voltage to output.
113 */
114 void SetVoltage(units::volt_t volts) override;
115 /**
116 * Common interface for getting the current set speed of a motor controller.
117 *
118 * \returns The current set speed. Value is between -1.0 and 1.0.
119 */
120 double Get() const override;
121 /**
122 * Common interface for disabling a motor controller.
123 */
124 void Disable() override;
125 /**
126 * Common interface to stop motor movement until Set is called again.
127 */
128 void StopMotor() override;
129 /**
130 * Common interface for inverting direction of a motor controller.
131 *
132 * \param isInverted The state of inversion, true is inverted.
133 */
134 void SetInverted(bool isInverted) override;
135 /**
136 * Common interface for returning the inversion state of a motor controller.
137 *
138 * \returns The state of the inversion, true is inverted.
139 */
140 bool GetInverted() const override;
141
142 /**
143 * \returns Description of motor controller
144 */
145 std::string GetDescription() const override;
146 void InitSendable(wpi::SendableBuilder &builder) override;
147
148protected:
149 //------------- Intercept CTRE calls for motor safety ------------//
150 ctre::phoenix::StatusCode SetControlPrivate(controls::ControlRequest &request) override;
151};
152
153}
154}
155}
Abstract Control Request class that other control requests extend for use.
Definition: ControlRequest.hpp:65
Request a specified motor duty cycle.
Definition: DutyCycleOut.hpp:28
Request neutral output of actuator.
Definition: NeutralOut.hpp:27
Request a specified voltage.
Definition: VoltageOut.hpp:29
Class description for the Talon FX integrated motor controller that runs on associated Falcon motors.
Definition: TalonFX.hpp:38
void Set(double speed) override
Common interface for setting the speed of a motor controller.
TalonFX(int deviceId, std::string canbus="")
Constructs a new Talon FX motor controller object.
void InitSendable(wpi::SendableBuilder &builder) override
void Disable() override
Common interface for disabling a motor controller.
ctre::phoenix::StatusCode SetControlPrivate(controls::ControlRequest &request) override
bool GetInverted() const override
Common interface for returning the inversion state of a motor controller.
void SetVoltage(units::volt_t volts) override
Common interface for seting the direct voltage output of a motor controller.
double Get() const override
Common interface for getting the current set speed of a motor controller.
void StopMotor() override
Common interface to stop motor movement until Set is called again.
void SetInverted(bool isInverted) override
Common interface for inverting direction of a motor controller.
std::string GetDescription() const override
Class description for the Talon FX integrated motor controller that runs on associated Falcon motors.
Definition: CoreTalonFX.hpp:1401
StatusSignalValue< units::dimensionless::scalar_t > & GetDutyCycle()
The applied motor duty cycle.
DeviceType
Enumeration of all supported device types.
Definition: DeviceType.hpp:26
Definition: string_util.hpp:14