Skip to content
Closed
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
17 changes: 9 additions & 8 deletions wpilibc/src/main/native/cpp/Servo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,27 +16,28 @@ constexpr double Servo::kMinServoAngle;
constexpr units::millisecond_t Servo::kDefaultMaxServoPWM;
constexpr units::millisecond_t Servo::kDefaultMinServoPWM;

Servo::Servo(int channel) : PWM(channel) {
Servo::Servo(int channel) : m_pwm(channel) {
// Set minimum and maximum PWM values supported by the servo
SetBounds(kDefaultMaxServoPWM, 0.0_ms, 0.0_ms, 0.0_ms, kDefaultMinServoPWM);
m_pwm.SetBounds(kDefaultMaxServoPWM, 0.0_ms, 0.0_ms, 0.0_ms,
kDefaultMinServoPWM);

// Assign defaults for period multiplier for the servo PWM control signal
SetPeriodMultiplier(kPeriodMultiplier_4X);
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_4X);

HAL_ReportUsage("IO", channel, "Servo");
wpi::SendableRegistry::SetName(this, "Servo", channel);
}

void Servo::Set(double value) {
SetPosition(value);
m_pwm.SetPosition(value);
}

void Servo::SetOffline() {
SetDisabled();
m_pwm.SetDisabled();
}

double Servo::Get() const {
return GetPosition();
return m_pwm.GetPosition();
}

void Servo::SetAngle(double degrees) {
Expand All @@ -46,11 +47,11 @@ void Servo::SetAngle(double degrees) {
degrees = kMaxServoAngle;
}

SetPosition((degrees - kMinServoAngle) / GetServoAngleRange());
m_pwm.SetPosition((degrees - kMinServoAngle) / GetServoAngleRange());
}

double Servo::GetAngle() const {
return GetPosition() * GetServoAngleRange() + kMinServoAngle;
return m_pwm.GetPosition() * GetServoAngleRange() + kMinServoAngle;
}

double Servo::GetMaxAngle() const {
Expand Down
6 changes: 5 additions & 1 deletion wpilibc/src/main/native/include/frc/Servo.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#pragma once

#include <units/angle.h>
#include <wpi/sendable/Sendable.h>

#include "frc/PWM.h"

Expand All @@ -16,7 +17,7 @@ namespace frc {
* The range parameters default to the appropriate values for the Hitec HS-322HD
* servo provided in the FIRST Kit of Parts in 2008.
*/
class Servo : public PWM {
class Servo : public wpi::Sendable {
public:
/**
* Constructor.
Expand Down Expand Up @@ -102,6 +103,9 @@ class Servo : public PWM {

void InitSendable(wpi::SendableBuilder& builder) override;

protected:
PWM m_pwm;

private:
double GetServoAngleRange() const;

Expand Down
28 changes: 18 additions & 10 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
package edu.wpi.first.wpilibj;

import edu.wpi.first.hal.HAL;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;

Expand All @@ -14,13 +15,15 @@
* <p>The range parameters default to the appropriate values for the Hitec HS-322HD servo provided
* in the FIRST Kit of Parts in 2008.
*/
public class Servo extends PWM {
public class Servo implements Sendable, AutoCloseable {
private static final double kMaxServoAngle = 180.0;
private static final double kMinServoAngle = 0.0;

private static final int kDefaultMaxServoPWM = 2400;
private static final int kDefaultMinServoPWM = 600;

protected PWM m_pwm;

/**
* Constructor.
*
Expand All @@ -32,12 +35,17 @@ public class Servo extends PWM {
*/
@SuppressWarnings("this-escape")
public Servo(final int channel) {
super(channel);
setBoundsMicroseconds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM);
setPeriodMultiplier(PeriodMultiplier.k4X);
m_pwm = new PWM(channel);
m_pwm.setBoundsMicroseconds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM);
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k4X);

HAL.reportUsage("IO", channel, "Servo");
SendableRegistry.setName(this, "Servo", channel);
}

HAL.reportUsage("IO", getChannel(), "Servo");
SendableRegistry.setName(this, "Servo", getChannel());
@Override
public void close() {
m_pwm.close();
}

/**
Expand All @@ -48,7 +56,7 @@ public Servo(final int channel) {
* @param value Position from 0.0 to 1.0.
*/
public void set(double value) {
setPosition(value);
m_pwm.setPosition(value);
}

/**
Expand All @@ -61,7 +69,7 @@ public void set(double value) {
* @return Position from 0.0 to 1.0.
*/
public double get() {
return getPosition();
return m_pwm.getPosition();
}

/**
Expand All @@ -83,7 +91,7 @@ public void setAngle(double degrees) {
degrees = kMaxServoAngle;
}

setPosition((degrees - kMinServoAngle) / getServoAngleRange());
m_pwm.setPosition((degrees - kMinServoAngle) / getServoAngleRange());
}

/**
Expand All @@ -95,7 +103,7 @@ public void setAngle(double degrees) {
* @return The angle in degrees to which the servo is set.
*/
public double getAngle() {
return getPosition() * getServoAngleRange() + kMinServoAngle;
return m_pwm.getPosition() * getServoAngleRange() + kMinServoAngle;
}

private double getServoAngleRange() {
Expand Down
Loading