Loading [MathJax]/extensions/tex2jax.js
CTRE Phoenix 6 C++ 23.10.0-alpha-8
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
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
10
11#include "frc/MotorSafety.h"
12#include "frc/motorcontrol/MotorController.h"
13#include "wpi/sendable/Sendable.h"
14#include "wpi/sendable/SendableBuilder.h"
15#include "wpi/sendable/SendableHelper.h"
16#include <hal/SimDevice.h>
17
18#include <string>
19
20namespace ctre {
21namespace phoenix6 {
22namespace hardware {
23
24/**
25 * Class description for the Talon FX integrated motor controller that runs on
26 * associated Falcon motors.
27 *
28 * This must be constructed after main executes. We recommend constructing inside
29 * the robot class or your subsystem classes. Otherwise WPILib motor safety may
30 * produce erroneous behavior.
31 */
33 public frc::MotorController,
34 public frc::MotorSafety,
35 public wpi::Sendable,
36 public wpi::SendableHelper<TalonFX>
37{
38 /**
39 * The StatusSignal getters are copies so that calls
40 * to the WPI interface do not update any references
41 *
42 * These are also mutable so the const getter methods are
43 * properly managed.
44 */
46
47 controls::DutyCycleOut m_setterControl{0.0};
48 controls::NeutralOut m_brakeRef{};
49 controls::VoltageOut m_voltageControl{0_V};
50
51 std::string m_description;
52
53 hal::SimDevice m_simMotor;
54 hal::SimDouble m_simSupplyVoltage;
55 hal::SimDouble m_simDutyCycle;
56 hal::SimDouble m_simMotorVoltage;
57 hal::SimDouble m_simTorqueCurrent;
58 hal::SimDouble m_simSupplyCurrent;
59
60 hal::SimDevice m_simForwardLimit;
61 hal::SimBoolean m_simForwardLimitValue;
62
63 hal::SimDevice m_simReverseLimit;
64 hal::SimBoolean m_simReverseLimitValue;
65
66 hal::SimDevice m_simRotor;
67 hal::SimDouble m_simRotorPos;
68 hal::SimDouble m_simRotorRawPos;
69 hal::SimDouble m_simRotorVel;
70
71 int32_t m_simPeriodicUid{-1};
72 std::vector<int32_t> m_simValueChangedUids;
73
74 static void OnValueChanged(const char* name, void *param, HAL_SimValueHandle handle,
75 HAL_Bool readonly, const struct HAL_Value* value);
76 static void OnPeriodic(void* param);
77
78public:
79 /**
80 * Constructs a new Talon FX motor controller object.
81 *
82 * This must be constructed after main executes. We recommend constructing inside
83 * the robot class or your subsystem classes. Otherwise WPILib motor safety may
84 * produce erroneous behavior.
85 *
86 * \param deviceId ID of the device, as configured in Phoenix Tuner.
87 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
88 * - "rio" for the native roboRIO CAN bus
89 * - CANivore name or serial number
90 * - SocketCAN interface (non-FRC Linux only)
91 * - "*" for any CANivore seen by the program
92 * - empty string (default) to select the default for the system:
93 * - "rio" on roboRIO
94 * - "can0" on Linux
95 * - "*" on Windows
96 */
97 TalonFX(int deviceId, std::string canbus = "");
99
100 /**
101 * Common interface for setting the speed of a motor controller.
102 *
103 * \param speed The speed to set. Value should be between -1.0 and 1.0.
104 */
105 void Set(double speed) override;
106 /**
107 * Common interface for seting the direct voltage output of a motor controller.
108 *
109 * \param volts The voltage to output.
110 */
111 void SetVoltage(units::volt_t volts) override;
112 /**
113 * Common interface for getting the current set speed of a motor controller.
114 *
115 * \returns The current set speed. Value is between -1.0 and 1.0.
116 */
117 double Get() const override;
118 /**
119 * Common interface for disabling a motor controller.
120 */
121 void Disable() override;
122 /**
123 * Common interface to stop motor movement until Set is called again.
124 */
125 void StopMotor() override;
126 /**
127 * Common interface for inverting direction of a motor controller.
128 *
129 * Since invert is a config, this API is blocking. We recommend that
130 * users avoid calling this API periodically.
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 * Since invert is a config, this API is blocking. We recommend that
139 * users avoid calling this API periodically.
140 *
141 * \returns The state of the inversion, true is inverted.
142 */
143 bool GetInverted() const override;
144
145 /**
146 * \returns Description of motor controller
147 */
148 std::string GetDescription() const override;
149 void InitSendable(wpi::SendableBuilder &builder) override;
150
151protected:
152 //------------- Intercept CTRE calls for motor safety ------------//
153 ctre::phoenix::StatusCode SetControlPrivate(controls::ControlRequest &request) override;
154};
155
156}
157}
158}
Abstract Control Request class that other control requests extend for use.
Definition: ControlRequest.hpp:28
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:37
std::string GetDescription() const override
ctre::phoenix::StatusCode SetControlPrivate(controls::ControlRequest &request) override
void SetInverted(bool isInverted) override
Common interface for inverting direction of a motor controller.
void StopMotor() override
Common interface to stop motor movement until Set is called again.
void Disable() override
Common interface for disabling a motor controller.
void InitSendable(wpi::SendableBuilder &builder) override
TalonFX(int deviceId, std::string canbus="")
Constructs a new Talon FX motor controller object.
void SetVoltage(units::volt_t volts) override
Common interface for seting the direct voltage output of a motor controller.
bool GetInverted() const override
Common interface for returning the inversion state of a motor controller.
void Set(double speed) override
Common interface for setting the speed of a motor controller.
double Get() const override
Common interface for getting the current set speed of a motor controller.
Class description for the Talon FX integrated motor controller that runs on associated Falcon motors.
Definition: CoreTalonFX.hpp:2367
StatusSignal< units::dimensionless::scalar_t > & GetDutyCycle()
The applied motor duty cycle.
Definition: ManualEvent.hpp:12