Skip to content
Open
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
10 changes: 9 additions & 1 deletion src/HW-Devices/hardware/include/TalonSRXWrapper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,9 @@ class TalonSRXWrapper : public BaseWrapper {
static void setup();

private:
enum class SensorType { PWM, RELATIVE, ANALOG };
enum class SensorType { PWM, RELATIVE, ANALOG, NONE };
static SensorType sensor_type_from_str(std::string str);
int get_load_enc() const;

// Parameters
int id_;
Expand All @@ -51,6 +53,7 @@ class TalonSRXWrapper : public BaseWrapper {
double sensor_offset_ticks_;
ctre::phoenix::motorcontrol::ControlMode control_type_;
SensorType sensor_type_;
SensorType load_sensor_;
int sensor_ticks_;
bool crossover_mode_;
bool inverted_;
Expand All @@ -59,6 +62,11 @@ class TalonSRXWrapper : public BaseWrapper {
rclcpp::Time start_time_;
rclcpp::Publisher<ros_phoenix::msg::MotorStatus>::SharedPtr debug_pub_;
static constexpr double kWaitDurationSec = 5.0;
static inline std::map<std::string, SensorType> sensor_type_map = {
{"quadrature", SensorType::RELATIVE},
{"absolute", SensorType::PWM},
{"analog", SensorType::ANALOG},
{"none", SensorType::NONE}};

// Talon-specific handle
std::shared_ptr<ctre::phoenix::motorcontrol::can::TalonSRX> talon_controller_;
Expand Down
43 changes: 32 additions & 11 deletions src/HW-Devices/hardware/src/TalonSRXWrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,9 @@ TalonSRXWrapper::TalonSRXWrapper(const hardware_interface::ComponentInfo &joint,
if (param.first == "can_id") {
id_ = std::stoi(param.second);
} else if (param.first == "sensor_type") {
sensor_type_str = param.second;
sensor_type_ = sensor_type_from_str(param.second);
} else if (param.first == "load_sensor") {
load_sensor_ = sensor_type_from_str(param.second);
} else if (param.first == "sensor_ticks") {
sensor_ticks_ = std::stoi(param.second);
} else if (param.first == "sensor_offset") {
Expand Down Expand Up @@ -77,20 +79,21 @@ TalonSRXWrapper::TalonSRXWrapper(const hardware_interface::ComponentInfo &joint,
debug_pub_ = debug_node_->create_publisher<ros_phoenix::msg::MotorStatus>(
joint.name + "/status", rclcpp::SystemDefaultsQoS());

std::transform(sensor_type_str.begin(), sensor_type_str.end(),
sensor_type_str.begin(),
[](unsigned char c) { return std::tolower(c); });
if (sensor_type_str == "quadrature") {
sensor_type_ = SensorType::RELATIVE;
} else if (sensor_type_str == "absolute") {
sensor_type_ = SensorType::PWM;
} else if (sensor_type_str == "analog") {
sensor_type_ = SensorType::ANALOG;
}
sensor_offset_ticks_ =
static_cast<int>(sensor_offset * sensor_ticks_ / (2.0 * M_PI));
}

TalonSRXWrapper::SensorType
TalonSRXWrapper::sensor_type_from_str(std::string str) {
std::transform(str.begin(), str.end(), str.begin(),
[](unsigned char c) { return std::tolower(c); });
const auto itr = sensor_type_map.find(str);
if (itr == sensor_type_map.end()) {
return SensorType::NONE;
}
return itr->second;
}

void TalonSRXWrapper::pub_status() const {
if (!talon_controller_ || !debug_pub_) {
return;
Expand Down Expand Up @@ -176,6 +179,21 @@ void TalonSRXWrapper::read() {
velocity_ = raw_velocity * 10 * (2.0 * M_PI) / sensor_ticks_;
}

int TalonSRXWrapper::get_load_enc() const {
auto &sensor_collection = talon_controller_->GetSensorCollection();
int abs_ticks = 0;
switch (load_sensor_) {
case SensorType::PWM:
return sensor_collection.GetPulseWidthPosition();
case SensorType::ANALOG:
return sensor_collection.GetAnalogIn();
case SensorType::RELATIVE:
return sensor_collection.GetQuadraturePosition();
default:
return 0;
}
}

void TalonSRXWrapper::configure() {
BaseWrapper::configure();
while (true) {
Expand Down Expand Up @@ -233,6 +251,9 @@ void TalonSRXWrapper::configure() {
talon_controller_->SetStatusFramePeriod(
StatusFrameEnhanced::Status_2_Feedback0, 20);
talon_controller_->SetIntegralAccumulator(0);
if (load_sensor_ != SensorType::NONE) {
talon_controller_->SetSelectedSensorPosition(get_load_enc());
}
read();
if (control_type_ == motors::ControlMode::Position) {
command_ = position_;
Expand Down
20 changes: 12 additions & 8 deletions src/URDF/rover_urdf/urdf/arm_urdf.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,10 @@
<param name="kI">0.0005</param>
<param name="kD">1.0</param>
<param name="kF">0.0</param>
<param name="sensor_type">absolute</param> <!-- or "quadrature" -->
<param name="sensor_type">quadrature</param> <!-- or "quadrature" -->
<param name="load_sensor">absolute</param>
<param name="sensor_ticks">4096</param>
<param name="sensor_offset">0.0</param>
<param name="sensor_offset">4.99</param>
<param name="crossover">false</param> <!-- or "continuous" -->
<param name="invert">false</param>
<param name="invert_sensor">false</param>
Expand All @@ -31,9 +32,10 @@
<param name="kI">0.001</param>
<param name="kD">0.01</param>
<param name="kF">0.0</param>
<param name="sensor_type">absolute</param> <!-- or "quadrature" -->
<param name="sensor_type">quadrature</param>
<param name="load_sensor">absolute</param>
<param name="sensor_ticks">4096</param>
<param name="sensor_offset">0.0</param>
<param name="sensor_offset">1.9</param>
<param name="crossover">false</param> <!-- or "continuous" -->
<param name="invert">false</param>
<param name="invert_sensor">false</param>
Expand All @@ -48,9 +50,10 @@
<param name="kI">0.001</param>
<param name="kD">0.0</param>
<param name="kF">0.0</param>
<param name="sensor_type">absolute</param> <!-- or "quadrature" -->
<param name="sensor_type">quadrature</param>
<param name="load_sensor">absolute</param>
<param name="sensor_ticks">4096</param>
<param name="sensor_offset">0.0</param>
<param name="sensor_offset">4.69494</param>
<param name="crossover">false</param> <!-- or "continuous" -->
<param name="invert">true</param>
<param name="invert_sensor">true</param>
Expand All @@ -65,9 +68,10 @@
<param name="kI">0.001</param>
<param name="kD">0.001</param>
<param name="kF">0.0</param>
<param name="sensor_type">absolute</param> <!-- or "quadrature" -->
<param name="sensor_type">quadrature</param>
<param name="load_sensor">absolute</param>
<param name="sensor_ticks">4096</param>
<param name="sensor_offset">0.0</param>
<param name="sensor_offset">3.26377</param>
<param name="crossover">false</param> <!-- or "continuous" -->
<param name="invert">false</param>
<param name="invert_sensor">false</param>
Expand Down
Loading