Skip to content

Commit

Permalink
Merge pull request #311 from firesurfer/ros2
Browse files Browse the repository at this point in the history
Resolve Symlinks
  • Loading branch information
flynneva authored Jan 20, 2024
2 parents f5d3e5b + ca58339 commit e2b11ab
Showing 1 changed file with 11 additions and 2 deletions.
13 changes: 11 additions & 2 deletions src/ros2/usb_cam_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#include <sstream>
#include <string>
#include <vector>

#include <filesystem>
#include "usb_cam/usb_cam_node.hpp"
#include "usb_cam/utils.hpp"

Expand Down Expand Up @@ -121,6 +121,15 @@ void UsbCamNode::service_capture(
}
}

std::string resolve_device_path(const std::string & path)
{
if (std::filesystem::is_symlink(path)) {
// For some reason read_symlink only returns videox
return "/dev/" + std::string(std::filesystem::read_symlink(path));
}
return path;
}

void UsbCamNode::init()
{
while (m_parameters.frame_id == "") {
Expand Down Expand Up @@ -246,7 +255,7 @@ void UsbCamNode::assign_params(const std::vector<rclcpp::Parameter> & parameters
} else if (parameter.get_name() == "av_device_format") {
m_parameters.av_device_format = parameter.value_to_string();
} else if (parameter.get_name() == "video_device") {
m_parameters.device_name = parameter.value_to_string();
m_parameters.device_name = resolve_device_path(parameter.value_to_string());
} else if (parameter.get_name() == "brightness") {
m_parameters.brightness = parameter.as_int();
} else if (parameter.get_name() == "contrast") {
Expand Down

0 comments on commit e2b11ab

Please sign in to comment.