WPILibC++ 2023.4.3-108-ge5452e3
ComputerVisionUtil.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <wpi/SymbolExports.h>
8
11
12namespace frc {
13
14/**
15 * Returns the robot's pose in the field coordinate system given an object's
16 * field-relative pose, the transformation from the camera's pose to the
17 * object's pose (obtained via computer vision), and the transformation from the
18 * robot's pose to the camera's pose.
19 *
20 * The object could be a target or a fiducial marker.
21 *
22 * @param objectInField An object's field-relative pose.
23 * @param cameraToObject The transformation from the camera's pose to the
24 * object's pose. This comes from computer vision.
25 * @param robotToCamera The transformation from the robot's pose to the camera's
26 * pose. This can either be a constant for a rigidly mounted camera, or
27 * variable if the camera is mounted to a turret. If the camera was mounted 3
28 * inches in front of the "origin" (usually physical center) of the robot,
29 * this would be frc::Transform3d{3_in, 0_in, 0_in, frc::Rotation3d{}}.
30 * @return The robot's field-relative pose.
31 */
34 const frc::Transform3d& cameraToObject,
35 const frc::Transform3d& robotToCamera);
36
37} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 3D pose containing translational and rotational elements.
Definition: Pose3d.h:23
Represents a transformation for a Pose3d.
Definition: Transform3d.h:18
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT frc::Pose3d ObjectToRobotPose(const frc::Pose3d &objectInField, const frc::Transform3d &cameraToObject, const frc::Transform3d &robotToCamera)
Returns the robot's pose in the field coordinate system given an object's field-relative pose,...