2020-12-26 14:12:05 -08:00
|
|
|
// Copyright (c) FIRST and other WPILib contributors.
|
|
|
|
|
// Open Source Software; you can modify and/or share it under the terms of
|
|
|
|
|
// the WPILib BSD license file in the root directory of this project.
|
2020-10-30 13:55:38 -07:00
|
|
|
|
|
|
|
|
package edu.wpi.first.wpilibj.smartdashboard;
|
|
|
|
|
|
2025-10-29 03:18:55 +00:00
|
|
|
import static edu.wpi.first.units.Units.Meters;
|
|
|
|
|
|
2021-05-01 15:53:30 +00:00
|
|
|
import edu.wpi.first.math.geometry.Pose2d;
|
|
|
|
|
import edu.wpi.first.math.geometry.Rotation2d;
|
|
|
|
|
import edu.wpi.first.math.geometry.Translation2d;
|
|
|
|
|
import edu.wpi.first.math.trajectory.Trajectory;
|
2022-10-08 10:01:31 -07:00
|
|
|
import edu.wpi.first.networktables.DoubleArrayEntry;
|
2025-10-29 03:18:55 +00:00
|
|
|
import edu.wpi.first.units.measure.Distance;
|
2020-12-29 22:45:16 -08:00
|
|
|
import java.util.ArrayList;
|
2023-12-03 16:21:32 -08:00
|
|
|
import java.util.Collections;
|
2020-12-29 22:45:16 -08:00
|
|
|
import java.util.List;
|
2020-10-30 13:55:38 -07:00
|
|
|
|
2020-12-29 22:45:16 -08:00
|
|
|
/** Game field object on a Field2d. */
|
2022-10-08 10:01:31 -07:00
|
|
|
public class FieldObject2d implements AutoCloseable {
|
2020-10-30 13:55:38 -07:00
|
|
|
/**
|
|
|
|
|
* Package-local constructor.
|
|
|
|
|
*
|
|
|
|
|
* @param name name
|
|
|
|
|
*/
|
|
|
|
|
FieldObject2d(String name) {
|
|
|
|
|
m_name = name;
|
|
|
|
|
}
|
|
|
|
|
|
2022-10-08 10:01:31 -07:00
|
|
|
@Override
|
|
|
|
|
public void close() {
|
2022-11-12 16:51:41 -08:00
|
|
|
if (m_entry != null) {
|
|
|
|
|
m_entry.close();
|
|
|
|
|
}
|
2022-10-08 10:01:31 -07:00
|
|
|
}
|
|
|
|
|
|
2020-10-30 13:55:38 -07:00
|
|
|
/**
|
|
|
|
|
* Set the pose from a Pose object.
|
|
|
|
|
*
|
|
|
|
|
* @param pose 2D pose
|
|
|
|
|
*/
|
|
|
|
|
public synchronized void setPose(Pose2d pose) {
|
|
|
|
|
setPoses(pose);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Set the pose from x, y, and rotation.
|
|
|
|
|
*
|
2025-02-10 07:23:04 -08:00
|
|
|
* @param x X location, in meters
|
|
|
|
|
* @param y Y location, in meters
|
2020-10-30 13:55:38 -07:00
|
|
|
* @param rotation rotation
|
|
|
|
|
*/
|
2025-02-10 07:23:04 -08:00
|
|
|
public synchronized void setPose(double x, double y, Rotation2d rotation) {
|
|
|
|
|
setPose(new Pose2d(x, y, rotation));
|
2020-10-30 13:55:38 -07:00
|
|
|
}
|
|
|
|
|
|
2025-10-29 03:18:55 +00:00
|
|
|
/**
|
|
|
|
|
* Set the pose from x, y, and rotation.
|
|
|
|
|
*
|
|
|
|
|
* @param x X location
|
|
|
|
|
* @param y Y location
|
|
|
|
|
* @param rotation rotation
|
|
|
|
|
*/
|
|
|
|
|
public synchronized void setPose(Distance x, Distance y, Rotation2d rotation) {
|
|
|
|
|
setPose(new Pose2d(x.in(Meters), y.in(Meters), rotation));
|
|
|
|
|
}
|
|
|
|
|
|
2020-10-30 13:55:38 -07:00
|
|
|
/**
|
|
|
|
|
* Get the pose.
|
|
|
|
|
*
|
|
|
|
|
* @return 2D pose
|
|
|
|
|
*/
|
|
|
|
|
public synchronized Pose2d getPose() {
|
|
|
|
|
updateFromEntry();
|
|
|
|
|
if (m_poses.isEmpty()) {
|
2024-05-03 12:39:35 -07:00
|
|
|
return Pose2d.kZero;
|
2020-10-30 13:55:38 -07:00
|
|
|
}
|
|
|
|
|
return m_poses.get(0);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
2022-12-26 14:32:13 -05:00
|
|
|
* Set multiple poses from a list of Pose objects. The total number of poses is limited to 85.
|
2020-10-30 13:55:38 -07:00
|
|
|
*
|
|
|
|
|
* @param poses list of 2D poses
|
|
|
|
|
*/
|
|
|
|
|
public synchronized void setPoses(List<Pose2d> poses) {
|
|
|
|
|
m_poses.clear();
|
2023-12-03 16:21:32 -08:00
|
|
|
m_poses.addAll(poses);
|
2020-10-30 13:55:38 -07:00
|
|
|
updateEntry();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
2022-12-26 14:32:13 -05:00
|
|
|
* Set multiple poses from a list of Pose objects. The total number of poses is limited to 85.
|
2020-10-30 13:55:38 -07:00
|
|
|
*
|
|
|
|
|
* @param poses list of 2D poses
|
|
|
|
|
*/
|
|
|
|
|
public synchronized void setPoses(Pose2d... poses) {
|
|
|
|
|
m_poses.clear();
|
2023-12-03 16:21:32 -08:00
|
|
|
Collections.addAll(m_poses, poses);
|
2020-10-30 13:55:38 -07:00
|
|
|
updateEntry();
|
|
|
|
|
}
|
|
|
|
|
|
2021-04-02 01:08:07 -04:00
|
|
|
/**
|
|
|
|
|
* Sets poses from a trajectory.
|
|
|
|
|
*
|
|
|
|
|
* @param trajectory The trajectory from which the poses should be added.
|
|
|
|
|
*/
|
|
|
|
|
public synchronized void setTrajectory(Trajectory trajectory) {
|
|
|
|
|
m_poses.clear();
|
|
|
|
|
for (Trajectory.State state : trajectory.getStates()) {
|
2025-02-10 07:23:04 -08:00
|
|
|
m_poses.add(state.pose);
|
2021-04-02 01:08:07 -04:00
|
|
|
}
|
|
|
|
|
updateEntry();
|
|
|
|
|
}
|
|
|
|
|
|
2020-10-30 13:55:38 -07:00
|
|
|
/**
|
|
|
|
|
* Get multiple poses.
|
|
|
|
|
*
|
|
|
|
|
* @return list of 2D poses
|
|
|
|
|
*/
|
|
|
|
|
public synchronized List<Pose2d> getPoses() {
|
|
|
|
|
updateFromEntry();
|
2023-12-03 16:21:32 -08:00
|
|
|
return new ArrayList<>(m_poses);
|
2020-10-30 13:55:38 -07:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void updateEntry() {
|
|
|
|
|
updateEntry(false);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
synchronized void updateEntry(boolean setDefault) {
|
|
|
|
|
if (m_entry == null) {
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
2022-10-08 10:01:31 -07:00
|
|
|
double[] arr = new double[m_poses.size() * 3];
|
|
|
|
|
int ndx = 0;
|
|
|
|
|
for (Pose2d pose : m_poses) {
|
|
|
|
|
Translation2d translation = pose.getTranslation();
|
|
|
|
|
arr[ndx + 0] = translation.getX();
|
|
|
|
|
arr[ndx + 1] = translation.getY();
|
|
|
|
|
arr[ndx + 2] = pose.getRotation().getDegrees();
|
|
|
|
|
ndx += 3;
|
|
|
|
|
}
|
[glass] Field2d enhancements (#3234)
- Add raw support for pose lists > 255/3 in length
- Improve drag selection, especially with closely overlapping objects
- Drag selection of corner also highlights center of object with smaller circle
- Multiple styles (box, line, closed line, track)
- Configurable line and arrow settings (color, weight)
- Add tooltip for object name, index, x, y, rotation
- Context menu for pose edit/add/remove
- View/edit in feet or inches as well as meters
- Configurable object selectability
Implementation: use vector of Pose2d internally, use units
2021-03-27 13:34:44 -07:00
|
|
|
|
2022-10-08 10:01:31 -07:00
|
|
|
if (setDefault) {
|
|
|
|
|
m_entry.setDefault(arr);
|
2020-10-30 13:55:38 -07:00
|
|
|
} else {
|
2022-10-08 10:01:31 -07:00
|
|
|
m_entry.set(arr);
|
2020-10-30 13:55:38 -07:00
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private synchronized void updateFromEntry() {
|
|
|
|
|
if (m_entry == null) {
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
2023-12-03 16:21:32 -08:00
|
|
|
double[] arr = m_entry.get(null);
|
[glass] Field2d enhancements (#3234)
- Add raw support for pose lists > 255/3 in length
- Improve drag selection, especially with closely overlapping objects
- Drag selection of corner also highlights center of object with smaller circle
- Multiple styles (box, line, closed line, track)
- Configurable line and arrow settings (color, weight)
- Add tooltip for object name, index, x, y, rotation
- Context menu for pose edit/add/remove
- View/edit in feet or inches as well as meters
- Configurable object selectability
Implementation: use vector of Pose2d internally, use units
2021-03-27 13:34:44 -07:00
|
|
|
if (arr != null) {
|
|
|
|
|
if ((arr.length % 3) != 0) {
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
m_poses.clear();
|
|
|
|
|
for (int i = 0; i < arr.length; i += 3) {
|
|
|
|
|
m_poses.add(new Pose2d(arr[i], arr[i + 1], Rotation2d.fromDegrees(arr[i + 2])));
|
|
|
|
|
}
|
2020-10-30 13:55:38 -07:00
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
String m_name;
|
2022-10-08 10:01:31 -07:00
|
|
|
DoubleArrayEntry m_entry;
|
2020-12-05 11:46:54 -05:00
|
|
|
private final List<Pose2d> m_poses = new ArrayList<>();
|
2020-10-30 13:55:38 -07:00
|
|
|
}
|