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
6 changes: 3 additions & 3 deletions src/localization/get_field_relitive_position.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include "src/utils/log.h"
namespace localization {

auto ToFeildRelitivePosition(tag_detection_t tag_relative_position,
auto ToFieldRelitivePosition(tag_detection_t tag_relative_position,
frc::Transform3d camera_to_robot,
const frc::AprilTagFieldLayout& apriltag_layout,
bool verbose) -> tag_detection_t {
Expand Down Expand Up @@ -75,12 +75,12 @@ auto ExtrinsicsJsonToCameraToRobot(nlohmann::json extrinsics_json)
return robot_to_camera.Inverse();
}

auto ToFeildRelitivePosition(std::vector<tag_detection_t> detections,
auto ToFieldRelitivePosition(std::vector<tag_detection_t> detections,
frc::Transform3d camera_to_robot,
const frc::AprilTagFieldLayout& apriltag_layout,
bool verbose) -> std::vector<tag_detection_t> {
for (tag_detection_t& detection : detections) {
detection = ToFeildRelitivePosition(detection, camera_to_robot,
detection = ToFieldRelitivePosition(detection, camera_to_robot,
apriltag_layout, verbose);
}
return detections;
Expand Down
4 changes: 2 additions & 2 deletions src/localization/get_field_relitive_position.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,13 @@ static frc::AprilTagFieldLayout kapriltag_layout =
frc::AprilTagFieldLayout("/bos/constants/2026-rebuilt-welded.json");

// returns camera to robot
auto ToFeildRelitivePosition(
auto ToFieldRelitivePosition(
std::vector<tag_detection_t> detections, frc::Transform3d camera_to_robot,
const frc::AprilTagFieldLayout& apriltag_layout = kapriltag_layout,
bool verbose = false) -> std::vector<tag_detection_t>;

// returns camera to robot
auto ToFeildRelitivePosition(
auto ToFieldRelitivePosition(
tag_detection_t tag_relative_position, frc::Transform3d camera_to_robot,
const frc::AprilTagFieldLayout& apriltag_layout = kapriltag_layout,
bool verbose = false) -> tag_detection_t;
Expand Down
2 changes: 1 addition & 1 deletion src/localization/run_localization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ void run_localization(camera::CameraSource& source,
camera::timestamped_frame_t timestamped_frame = source.Get();
streamer.WriteFrame(timestamped_frame.frame);
std::vector<localization::tag_detection_t> estimates =
localization::ToFeildRelitivePosition(
localization::ToFieldRelitivePosition(
detector->GetTagDetections(timestamped_frame), camera_to_robot);
LOG(INFO) << estimates.size() << "estimate size";
position_sender.Send(estimates, timer.Stop());
Expand Down