REV Color Sensor V3
Detect colors and measure distances with the REV Color Sensor V3
Overview
The REV Color Sensor V3 (REV-31-1557) is a dual-purpose sensor featuring a Broadcom APDS-9151 chip that can:
- Detect Colors - Measure red, green, blue, and ambient light intensity (0-255 each)
- Measure Distance - Detect objects up to ~10cm away using time-of-flight technology
Hardware Version: The REV Color Sensor V3 is different from the older "REV Color/Range Sensor" (V1/V2). Make sure to select "REV Color Sensor V3" in your robot configuration, not "REV Color/Range Sensor"!
Dual Functionality: This sensor implements both ColorSensor and DistanceSensor interfaces, so you declare it twice in code using the same hardware map name!
Hardware Configuration
In the Robot Configuration
- Connect the sensor to an I2C port on your Control Hub or Expansion Hub
- In the Driver Station, go to Configure Robot
- Select the I2C Bus your sensor is connected to (typically I2C Bus 0 on the Control Hub)
- On the desired port (typically Port 0), select "REV Color Sensor V3" (not "REV Color/Range Sensor")
- Name it
"sensor_color"(or your preferred name, but avoid spaces) - Save the configuration
Configuration Name: Unlike older V1/V2 sensors configured as "REV Color/Range Sensor", the V3 has its own dedicated configuration option: "REV Color Sensor V3"
Basic Setup
Initializing the Sensor
Since the sensor acts as both a color and distance sensor, you need to declare it twice:
import com.qualcomm.robotcore.hardware.ColorSensor;
import com.qualcomm.robotcore.hardware.DistanceSensor;
import com.qualcomm.robotcore.hardware.NormalizedColorSensor;
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
public class RobotHardware {
private ColorSensor colorSensor;
private DistanceSensor distanceSensor;
private NormalizedColorSensor normalizedColorSensor;
public void init(HardwareMap hwMap) {
// Same name for all - the sensor implements multiple interfaces
colorSensor = hwMap.get(ColorSensor.class, "sensor_color");
distanceSensor = hwMap.get(DistanceSensor.class, "sensor_color");
normalizedColorSensor = hwMap.get(NormalizedColorSensor.class, "sensor_color");
// Optional: Set the gain for different lighting conditions
// Higher gain = more sensitive (better for dim lighting)
// Lower gain = less sensitive (better for bright lighting)
if (normalizedColorSensor != null) {
normalizedColorSensor.setGain(2); // Values typically 1-16
}
}
}import com.qualcomm.robotcore.hardware.ColorSensor
import com.qualcomm.robotcore.hardware.DistanceSensor
import com.qualcomm.robotcore.hardware.NormalizedColorSensor
import com.qualcomm.robotcore.hardware.NormalizedRGBA
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit
class RobotHardware {
private lateinit var colorSensor: ColorSensor
private lateinit var distanceSensor: DistanceSensor
private lateinit var normalizedColorSensor: NormalizedColorSensor
fun init(hwMap: HardwareMap) {
// Same name for all - the sensor implements multiple interfaces
colorSensor = hwMap.get(ColorSensor::class.java, "sensor_color")
distanceSensor = hwMap.get(DistanceSensor::class.java, "sensor_color")
normalizedColorSensor = hwMap.get(NormalizedColorSensor::class.java, "sensor_color")
// Optional: Set the gain for different lighting conditions
normalizedColorSensor.gain = 2f // Values typically 1-16
}
}Reading Color Values
RGB Values
The color sensor returns separate values for red, green, and blue light intensity:
// Get individual color channels (0-255)
int red = colorSensor.red();
int green = colorSensor.green();
int blue = colorSensor.blue();
int alpha = colorSensor.alpha(); // Ambient light/brightness
// Display to driver station
telemetry.addData("Red", red);
telemetry.addData("Green", green);
telemetry.addData("Blue", blue);
telemetry.addData("Alpha (brightness)", alpha);// Get individual color channels (0-255)
val red = colorSensor.red()
val green = colorSensor.green()
val blue = colorSensor.blue()
val alpha = colorSensor.alpha() // Ambient light/brightness
// Display to driver station
telemetry.addData("Red", red)
telemetry.addData("Green", green)
telemetry.addData("Blue", blue)
telemetry.addData("Alpha (brightness)", alpha)Normalized Colors (Recommended)
The V3 supports normalized colors which automatically adjust for lighting conditions:
// Get normalized colors (0.0 - 1.0 range)
NormalizedRGBA colors = normalizedColorSensor.getNormalizedColors();
telemetry.addLine()
.addData("Red", "%.3f", colors.red)
.addData("Green", "%.3f", colors.green)
.addData("Blue", "%.3f", colors.blue);
telemetry.addData("Alpha", "%.3f", colors.alpha);
// Convert to Android color for display
int color = colors.toColor();// Get normalized colors (0.0 - 1.0 range)
val colors = normalizedColorSensor.normalizedColors
telemetry.addLine()
.addData("Red", "%.3f", colors.red)
.addData("Green", "%.3f", colors.green)
.addData("Blue", "%.3f", colors.blue)
telemetry.addData("Alpha", "%.3f", colors.alpha)
// Convert to Android color for display
val color = colors.toColor()Adjusting Gain for Lighting Conditions
The V3's Broadcom chip allows adjusting sensitivity via gain:
// Adjust gain based on lighting
// Lower values (1-2): Bright competition lighting
// Medium values (4-8): Normal indoor lighting
// Higher values (12-16): Dim lighting
normalizedColorSensor.setGain(4); // Adjust as needed
// Get current gain
float currentGain = normalizedColorSensor.getGain();
telemetry.addData("Sensor Gain", currentGain);// Adjust gain based on lighting
normalizedColorSensor.gain = 4f // Adjust as needed
// Get current gain
val currentGain = normalizedColorSensor.gain
telemetry.addData("Sensor Gain", currentGain)ARGB Format
You can also get all color data as a single integer:
// Get color as a single integer (#aarrggbb)
int argb = colorSensor.argb();
// Extract individual channels
int alpha = (argb >> 24) & 0xFF;
int red = (argb >> 16) & 0xFF;
int green = (argb >> 8) & 0xFF;
int blue = argb & 0xFF;// Get color as a single integer (#aarrggbb)
val argb = colorSensor.argb()
// Extract individual channels
val alpha = (argb shr 24) and 0xFF
val red = (argb shr 16) and 0xFF
val green = (argb shr 8) and 0xFF
val blue = argb and 0xFFColorSensor Methods
| Method | Returns | Description |
|---|---|---|
red() | int (0-255) | Amount of red light detected |
green() | int (0-255) | Amount of green light detected |
blue() | int (0-255) | Amount of blue light detected |
alpha() | int (0-255) | Ambient light level (brightness) |
argb() | int | Color in #aarrggbb format |
getNormalizedColors() | NormalizedRGBA | Normalized color values (0.0-1.0) |
setGain(float) | void | Set sensor sensitivity (1-16) |
getGain() | float | Get current sensor gain |
Reading Distance
DistanceUnit Class
The SDK provides a DistanceUnit enum to handle unit conversions automatically:
// Get distance in different units
double distanceCm = distanceSensor.getDistance(DistanceUnit.CM);
double distanceInch = distanceSensor.getDistance(DistanceUnit.INCH);
double distanceMm = distanceSensor.getDistance(DistanceUnit.MM);
telemetry.addData("Distance (cm)", "%.2f", distanceCm);
telemetry.addData("Distance (in)", "%.2f", distanceInch);// Get distance in different units
val distanceCm = distanceSensor.getDistance(DistanceUnit.CM)
val distanceInch = distanceSensor.getDistance(DistanceUnit.INCH)
val distanceMm = distanceSensor.getDistance(DistanceUnit.MM)
telemetry.addData("Distance (cm)", "%.2f", distanceCm)
telemetry.addData("Distance (in)", "%.2f", distanceInch)Available Distance Units
| DistanceUnit | Description |
|---|---|
DistanceUnit.MM | Millimeters |
DistanceUnit.CM | Centimeters (recommended) |
DistanceUnit.INCH | Inches |
DistanceUnit.METER | Meters |
Unit Conversion: Store distances internally in one unit (typically CM) and use DistanceUnit methods like toCm() and fromCm() to convert as needed. This prevents unit conversion errors!
Complete Example
Here's a full OpMode demonstrating both color and distance sensing with the V3:
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.ColorSensor;
import com.qualcomm.robotcore.hardware.DistanceSensor;
import com.qualcomm.robotcore.hardware.NormalizedColorSensor;
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
@TeleOp(name = "Color Sensor V3 Demo")
public class ColorSensorV3Demo extends OpMode {
private ColorSensor colorSensor;
private DistanceSensor distanceSensor;
private NormalizedColorSensor normalizedColorSensor;
@Override
public void init() {
colorSensor = hardwareMap.get(ColorSensor.class, "sensor_color");
distanceSensor = hardwareMap.get(DistanceSensor.class, "sensor_color");
normalizedColorSensor = hardwareMap.get(NormalizedColorSensor.class, "sensor_color");
// Set gain for your lighting conditions
normalizedColorSensor.setGain(2);
telemetry.addLine("Color Sensor V3 initialized!");
telemetry.addData("Gain", normalizedColorSensor.getGain());
}
@Override
public void loop() {
// Read normalized colors (recommended)
NormalizedRGBA colors = normalizedColorSensor.getNormalizedColors();
// Read raw color values
int red = colorSensor.red();
int green = colorSensor.green();
int blue = colorSensor.blue();
int alpha = colorSensor.alpha();
// Read distance
double distanceCm = distanceSensor.getDistance(DistanceUnit.CM);
// Display normalized colors
telemetry.addLine("=== Normalized Colors (0.0-1.0) ===");
telemetry.addData("Red", "%.3f", colors.red);
telemetry.addData("Green", "%.3f", colors.green);
telemetry.addData("Blue", "%.3f", colors.blue);
telemetry.addData("Alpha", "%.3f", colors.alpha);
// Display raw values
telemetry.addLine("\n=== Raw Values (0-255) ===");
telemetry.addData("Red", red);
telemetry.addData("Green", green);
telemetry.addData("Blue", blue);
telemetry.addData("Alpha", alpha);
// Display distance
telemetry.addLine("\n=== Distance ===");
telemetry.addData("Distance (cm)", "%.2f", distanceCm);
// Detect primary color
String detectedColor = "Unknown";
if (red > green && red > blue) {
detectedColor = "Red";
} else if (green > red && green > blue) {
detectedColor = "Green";
} else if (blue > red && blue > green) {
detectedColor = "Blue";
}
telemetry.addLine("\n=== Detection ===");
telemetry.addData("Detected Color", detectedColor);
telemetry.addData("Object Nearby", distanceCm < 5);
}
}package org.firstinspires.ftc.teamcode
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.eventloop.opmode.TeleOp
import com.qualcomm.robotcore.hardware.ColorSensor
import com.qualcomm.robotcore.hardware.DistanceSensor
import com.qualcomm.robotcore.hardware.NormalizedColorSensor
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit
@TeleOp(name = "Color Sensor V3 Demo")
class ColorSensorV3Demo : OpMode() {
private lateinit var colorSensor: ColorSensor
private lateinit var distanceSensor: DistanceSensor
private lateinit var normalizedColorSensor: NormalizedColorSensor
override fun init() {
colorSensor = hardwareMap.get(ColorSensor::class.java, "sensor_color")
distanceSensor = hardwareMap.get(DistanceSensor::class.java, "sensor_color")
normalizedColorSensor = hardwareMap.get(NormalizedColorSensor::class.java, "sensor_color")
// Set gain for your lighting conditions
normalizedColorSensor.gain = 2f
telemetry.addLine("Color Sensor V3 initialized!")
telemetry.addData("Gain", normalizedColorSensor.gain)
}
override fun loop() {
// Read normalized colors (recommended)
val colors = normalizedColorSensor.normalizedColors
// Read raw color values
val red = colorSensor.red()
val green = colorSensor.green()
val blue = colorSensor.blue()
val alpha = colorSensor.alpha()
// Read distance
val distanceCm = distanceSensor.getDistance(DistanceUnit.CM)
// Display normalized colors
telemetry.addLine("=== Normalized Colors (0.0-1.0) ===")
telemetry.addData("Red", "%.3f", colors.red)
telemetry.addData("Green", "%.3f", colors.green)
telemetry.addData("Blue", "%.3f", colors.blue)
telemetry.addData("Alpha", "%.3f", colors.alpha)
// Display raw values
telemetry.addLine("\n=== Raw Values (0-255) ===")
telemetry.addData("Red", red)
telemetry.addData("Green", green)
telemetry.addData("Blue", blue)
telemetry.addData("Alpha", alpha)
// Display distance
telemetry.addLine("\n=== Distance ===")
telemetry.addData("Distance (cm)", "%.2f", distanceCm)
// Detect primary color
val detectedColor = when {
red > green && red > blue -> "Red"
green > red && green > blue -> "Green"
blue > red && blue > green -> "Blue"
else -> "Unknown"
}
telemetry.addLine("\n=== Detection ===")
telemetry.addData("Detected Color", detectedColor)
telemetry.addData("Object Nearby", distanceCm < 5)
}
}Practical Applications
Game Element Detection
Detect colored game pieces (ARTIFACTS in DECODE):
public enum ArtifactColor {
PURPLE,
GREEN,
UNKNOWN
}
public ArtifactColor detectArtifact() {
// Use normalized colors for better accuracy
NormalizedRGBA colors = normalizedColorSensor.getNormalizedColors();
// Check if object is close enough
if (distanceSensor.getDistance(DistanceUnit.CM) > 5) {
return ArtifactColor.UNKNOWN;
}
// Purple has high red and blue, low green
if (colors.red > 0.4 && colors.blue > 0.4 && colors.green < 0.3) {
return ArtifactColor.PURPLE;
}
// Green has high green, lower red and blue
if (colors.green > 0.4 && colors.red < 0.3 && colors.blue < 0.3) {
return ArtifactColor.GREEN;
}
return ArtifactColor.UNKNOWN;
}enum class ArtifactColor {
PURPLE,
GREEN,
UNKNOWN
}
fun detectArtifact(): ArtifactColor {
// Use normalized colors for better accuracy
val colors = normalizedColorSensor.normalizedColors
// Check if object is close enough
if (distanceSensor.getDistance(DistanceUnit.CM) > 5) {
return ArtifactColor.UNKNOWN
}
// Purple has high red and blue, low green
if (colors.red > 0.4 && colors.blue > 0.4 && colors.green < 0.3) {
return ArtifactColor.PURPLE
}
// Green has high green, lower red and blue
if (colors.green > 0.4 && colors.red < 0.3 && colors.blue < 0.3) {
return ArtifactColor.GREEN
}
return ArtifactColor.UNKNOWN
}Proximity-Based Motor Control
Control motor speed based on distance:
public void updateMotorBasedOnDistance() {
double distance = distanceSensor.getDistance(DistanceUnit.CM);
if (distance < 10) {
// Object very close - stop motor
motor.setPower(0);
} else if (distance < 20) {
// Object nearby - slow down
motor.setPower(0.5);
} else {
// Clear path - full speed
motor.setPower(1.0);
}
}fun updateMotorBasedOnDistance() {
val distance = distanceSensor.getDistance(DistanceUnit.CM)
when {
distance < 10 -> {
// Object very close - stop motor
motor.power = 0.0
}
distance < 20 -> {
// Object nearby - slow down
motor.power = 0.5
}
else -> {
// Clear path - full speed
motor.power = 1.0
}
}
}Alliance Color Detection
Detect red vs blue alliance colors:
public boolean isRedAlliance() {
NormalizedRGBA colors = normalizedColorSensor.getNormalizedColors();
// Red > Blue indicates red alliance
return colors.red > colors.blue;
}fun isRedAlliance(): Boolean {
val colors = normalizedColorSensor.normalizedColors
// Red > Blue indicates red alliance
return colors.red > colors.blue
}Tips and Best Practices
Lighting Conditions and Gain
Ambient Light: The V3's Broadcom chip performs better in varying lighting conditions than older sensors, but you should still test under competition lighting and adjust the gain as needed!
- White LED on the sensor provides consistent illumination
- Adjust gain based on competition venue (bright=lower gain, dim=higher gain)
- Use normalized colors (
getNormalizedColors()) instead of raw values when possible - Shield sensor from direct overhead lights if possible
- Calibrate color thresholds during practice matches
Distance Limitations
- Effective Range: 0-10cm (0-4 inches)
- Accuracy: Less accurate than dedicated REV 2M Distance Sensor
- Best Use: Close-range detection (intake sensors, game piece verification)
- Time-of-flight technology works best with solid, non-reflective surfaces
Performance Tips
- Use Normalized Colors:
getNormalizedColors()provides better consistency across lighting conditions - Set Appropriate Gain: Lower gain for bright environments (1-2), higher for dim (12-16)
- Read Only What You Need: Don't call
red(),green(),blue()every loop if you only need distance - Alpha Channel for Brightness: Use
alpha()orcolors.alphato monitor ambient light - Threshold Testing: Find reliable color thresholds experimentally - don't guess!
- Physical Mounting: Mount sensor 1-3cm from expected object position for best detection
V3-Specific Features
The Broadcom APDS-9151 chipset in the V3 offers:
- Better normalization of color values
- Improved alpha channel calculation (ambient brightness)
- Configurable resolution and measurement rate
- No IR interference (older sensors had issues with this)
Troubleshooting
"Sensor Not Found"
- Check I2C bus number in configuration (typically Bus 0 on Control Hub)
- Verify you selected "REV Color Sensor V3", not "REV Color/Range Sensor"
- Verify cable connections (4-wire JST PH connector)
- Ensure sensor name matches exactly in code and config
Inconsistent Color Readings
- Check gain setting: Too high = oversaturated, too low = insufficient sensitivity
- Use normalized colors: More reliable than raw values
- Check mounting position - sensor should be 1-3cm from objects
- Verify lighting conditions are consistent
- Average multiple readings to reduce noise (3-5 samples)
- Ensure sensor white LED is not blocked
Distance Always Returns 0 or Max
- Object may be outside 10cm range
- Check that you're using
DistanceSensorinterface, not justColorSensor - Verify sensor has clear line of sight
- Highly reflective or transparent objects may not read correctly
- Very dark objects may not reflect enough light
Colors Seem Washed Out or Too Dark
- Adjust gain:
normalizedColorSensor.setGain(value) - Start with gain of 2-4 and adjust based on your environment
- Higher gain for darker lighting, lower for brighter lighting
- Monitor the alpha channel to verify brightness levels