Skip to content

Commit

Permalink
Merge branch 'master' into tasks
Browse files Browse the repository at this point in the history
  • Loading branch information
abhaybd authored Jan 27, 2024
2 parents e6d4877 + cb74553 commit 82a2e9e
Show file tree
Hide file tree
Showing 5 changed files with 13 additions and 12 deletions.
4 changes: 2 additions & 2 deletions src/Constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,8 @@ const double MAX_DTHETA = kinematics::DiffDriveKinematics(EFF_WHEEL_BASE)

// TODO: We need to recalibrate the camera, since we replaced it with a different one.
// TODO: rename cameras (in MC as well) as appropriate
constexpr const char* AR_CAMERA_CONFIG_PATH = "../camera-config/MastCameraCalibration.yml";
const robot::types::CameraID AR_CAMERA_ID = "front"; // TODO: replace with real camera name
constexpr const char* MAST_CAMERA_CONFIG_PATH = "../camera-config/MastCameraCalibration.yml";
const robot::types::CameraID MAST_CAMERA_ID = "front"; // TODO: replace with real camera name

constexpr const char* FOREARM_CAMERA_CONFIG_PATH =
"../camera-config/ForearmCameraCalibration.yml";
Expand Down
11 changes: 6 additions & 5 deletions src/ar/read_landmarks.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ void detectLandmarksLoop() {
cv::Mat frame;
uint32_t last_frame_no = 0;
while (true) {
if (robot::hasNewCameraFrame(Constants::AR_CAMERA_ID, last_frame_no)) {
auto camData = robot::readCamera(Constants::AR_CAMERA_ID);
if (robot::hasNewCameraFrame(Constants::MAST_CAMERA_ID, last_frame_no)) {
auto camData = robot::readCamera(Constants::MAST_CAMERA_ID);
if (!camData)
continue;
auto camFrame = camData.getData();
Expand Down Expand Up @@ -65,7 +65,8 @@ void detectLandmarksLoop() {
cv::Vec3d coords = ids_to_camera_coords[id];
// if we have extrinsic parameters, multiply coordinates by them to do
// appropriate transformation.
auto extrinsic = robot::getCameraExtrinsicParams(Constants::AR_CAMERA_ID);
auto extrinsic =
robot::getCameraExtrinsicParams(Constants::MAST_CAMERA_ID);
if (extrinsic) {
cv::Vec4d coords_homogeneous = {coords[0], coords[1], coords[2], 1};
cv::Mat transformed = extrinsic.value() * cv::Mat(coords_homogeneous);
Expand Down Expand Up @@ -99,7 +100,7 @@ void detectLandmarksLoop() {
}

bool initializeLandmarkDetection() {
auto intrinsic = robot::getCameraIntrinsicParams(Constants::AR_CAMERA_ID);
auto intrinsic = robot::getCameraIntrinsicParams(Constants::MAST_CAMERA_ID);
if (intrinsic) {
ar_detector = Detector(Markers::URC_MARKERS(), intrinsic.value());
landmark_thread = std::thread(&detectLandmarksLoop);
Expand All @@ -108,7 +109,7 @@ bool initializeLandmarkDetection() {
"cannot be performed.");
return false;
}
if (!robot::getCameraExtrinsicParams(Constants::AR_CAMERA_ID)) {
if (!robot::getCameraExtrinsicParams(Constants::MAST_CAMERA_ID)) {
LOG_F(WARNING, "Camera does not have extrinsic parameters! Coordinates returned "
"for AR tags will be relative to camera");
}
Expand Down
2 changes: 1 addition & 1 deletion src/world_interface/real_world_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ void openCamera(CameraID camID, const char* cameraPath) {
}

void setupCameras() {
openCamera(Constants::AR_CAMERA_ID, Constants::AR_CAMERA_CONFIG_PATH);
openCamera(Constants::MAST_CAMERA_ID, Constants::MAST_CAMERA_CONFIG_PATH);
openCamera(Constants::HAND_CAMERA_ID, Constants::HAND_CAMERA_CONFIG_PATH);
}
} // namespace
Expand Down
6 changes: 3 additions & 3 deletions src/world_interface/simulator_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,9 +104,9 @@ static void openCamera(CameraID cam, std::optional<std::vector<double>> list1d =
}

void initCameras() {
auto cfg = cam::readConfigFromFile(Constants::AR_CAMERA_CONFIG_PATH);
cameraConfigMap[Constants::AR_CAMERA_ID] = cfg;
// openCamera(Constants::AR_CAMERA_ID);
auto cfg = cam::readConfigFromFile(Constants::MAST_CAMERA_CONFIG_PATH);
cameraConfigMap[Constants::MAST_CAMERA_ID] = cfg;
// openCamera(Constants::MAST_CAMERA_ID);
openCamera("front", cfg.intrinsicParams->getIntrinsicList());
openCamera("rear", cfg.intrinsicParams->getIntrinsicList());
openCamera("upperArm", cfg.intrinsicParams->getIntrinsicList());
Expand Down
2 changes: 1 addition & 1 deletion tests/camera/CameraParamsTests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ TEST_CASE("Serialization works", "[camera][camera_params]") {
TEST_CASE("List Conversation Works"){
std::unordered_map<robot::types::CameraID, cam::CameraConfig> cameraConfigMap;
auto cfg = cam::readConfigFromFile("../camera-config/global.yml");
cameraConfigMap[Constants::AR_CAMERA_ID] = cfg;
cameraConfigMap[Constants::MAST_CAMERA_ID] = cfg;
std::vector<double> x1 = cfg.intrinsicParams->getIntrinsicList();
std::vector<double> x1test {8.2342295124138286e+02, 0., 3.0932599345522056e+02, 0.,
8.2343518498999936e+02, 2.5535163960018482e+02, 0., 0., 1.};
Expand Down

0 comments on commit 82a2e9e

Please sign in to comment.