Skip to content

Commit

Permalink
Add optional namespace to /set_camera_info service in CameraInfoManag…
Browse files Browse the repository at this point in the history
…er (#324)
  • Loading branch information
jasiex01 authored Sep 25, 2024
1 parent ea6a9e4 commit 3b0a1b6
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -155,6 +155,13 @@ using SetCameraInfo = sensor_msgs::srv::SetCameraInfo;
will be stored there, missing parent directories being created if
necessary and possible.
@par Namespace
The CameraInfoManager constructor takes an optional namespace
argument, which is used to set the ROS namespace for the
set_camera_info service. If not provided, the namespace defaults
to the private namespace of the node (i.e., "~/set_camera_info").
@par Loading Calibration Data
Prior to Fuerte, calibration information was loaded in the
Expand All @@ -178,21 +185,24 @@ class CameraInfoManager
CameraInfoManager(
rclcpp::Node * node,
const std::string & cname = "camera",
const std::string & url = "");
const std::string & url = "",
const std::string & ns = "~");

CAMERA_INFO_MANAGER_PUBLIC
CameraInfoManager(
rclcpp_lifecycle::LifecycleNode * node,
const std::string & cname = "camera",
const std::string & url = "");
const std::string & url = "",
const std::string & ns = "~");

CAMERA_INFO_MANAGER_PUBLIC
CameraInfoManager(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logger_interface,
const std::string & cname = "camera", const std::string & url = "",
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
const std::string & ns = "~");

CAMERA_INFO_MANAGER_PUBLIC
CameraInfo getCameraInfo(void);
Expand Down Expand Up @@ -272,6 +282,7 @@ class CameraInfoManager
rclcpp::Logger logger_; ///< logger
std::string camera_name_; ///< camera name
std::string url_; ///< URL for calibration data
std::string namespace_; ///< ROS namespace set_camera_info service
CameraInfo cam_info_; ///< current CameraInfo
bool loaded_cam_info_; ///< cam_info_ load attempted
}; // class CameraInfoManager
Expand Down
19 changes: 13 additions & 6 deletions camera_info_manager/src/camera_info_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,38 +69,45 @@ const std::string
* subordinate names, like "left/camera" and "right/camera".
* @param cname default camera name
* @param url default Uniform Resource Locator for loading and saving data.
* @param ns namespace for the set_camera_info service. If not specified,
* the service name will be "~/set_camera_info".
*/
CameraInfoManager::CameraInfoManager(
rclcpp::Node * node, const std::string & cname,
const std::string & url)
const std::string & url, const std::string & ns)
: CameraInfoManager(node->get_node_base_interface(),
node->get_node_services_interface(), node->get_node_logging_interface(), cname, url)
node->get_node_services_interface(), node->get_node_logging_interface(), cname, url,
rmw_qos_profile_default, ns)
{
}

CameraInfoManager::CameraInfoManager(
rclcpp_lifecycle::LifecycleNode * node,
const std::string & cname, const std::string & url)
const std::string & cname, const std::string & url,
const std::string & ns)
: CameraInfoManager(node->get_node_base_interface(),
node->get_node_services_interface(), node->get_node_logging_interface(), cname, url)
node->get_node_services_interface(), node->get_node_logging_interface(), cname, url,
rmw_qos_profile_default, ns)
{
}

CameraInfoManager::CameraInfoManager(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logger_interface,
const std::string & cname, const std::string & url, rmw_qos_profile_t custom_qos)
const std::string & cname, const std::string & url,
rmw_qos_profile_t custom_qos, const std::string & ns)
: logger_(node_logger_interface->get_logger()),
camera_name_(cname),
url_(url),
namespace_(ns),
loaded_cam_info_(false)
{
using namespace std::placeholders;

// register callback for camera calibration service request
info_service_ = rclcpp::create_service<SetCameraInfo>(
node_base_interface, node_services_interface, "~/set_camera_info",
node_base_interface, node_services_interface, namespace_ + "/set_camera_info",
std::bind(&CameraInfoManager::setCameraInfoService, this, _1, _2), custom_qos, nullptr);
}

Expand Down

0 comments on commit 3b0a1b6

Please sign in to comment.