Skip to content

Commit 3b0a1b6

Browse files
authored
Add optional namespace to /set_camera_info service in CameraInfoManager (#324)
1 parent ea6a9e4 commit 3b0a1b6

File tree

2 files changed

+27
-9
lines changed

2 files changed

+27
-9
lines changed

camera_info_manager/include/camera_info_manager/camera_info_manager.hpp

Lines changed: 14 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -155,6 +155,13 @@ using SetCameraInfo = sensor_msgs::srv::SetCameraInfo;
155155
will be stored there, missing parent directories being created if
156156
necessary and possible.
157157
158+
@par Namespace
159+
160+
The CameraInfoManager constructor takes an optional namespace
161+
argument, which is used to set the ROS namespace for the
162+
set_camera_info service. If not provided, the namespace defaults
163+
to the private namespace of the node (i.e., "~/set_camera_info").
164+
158165
@par Loading Calibration Data
159166
160167
Prior to Fuerte, calibration information was loaded in the
@@ -178,21 +185,24 @@ class CameraInfoManager
178185
CameraInfoManager(
179186
rclcpp::Node * node,
180187
const std::string & cname = "camera",
181-
const std::string & url = "");
188+
const std::string & url = "",
189+
const std::string & ns = "~");
182190

183191
CAMERA_INFO_MANAGER_PUBLIC
184192
CameraInfoManager(
185193
rclcpp_lifecycle::LifecycleNode * node,
186194
const std::string & cname = "camera",
187-
const std::string & url = "");
195+
const std::string & url = "",
196+
const std::string & ns = "~");
188197

189198
CAMERA_INFO_MANAGER_PUBLIC
190199
CameraInfoManager(
191200
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
192201
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
193202
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logger_interface,
194203
const std::string & cname = "camera", const std::string & url = "",
195-
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);
204+
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
205+
const std::string & ns = "~");
196206

197207
CAMERA_INFO_MANAGER_PUBLIC
198208
CameraInfo getCameraInfo(void);
@@ -272,6 +282,7 @@ class CameraInfoManager
272282
rclcpp::Logger logger_; ///< logger
273283
std::string camera_name_; ///< camera name
274284
std::string url_; ///< URL for calibration data
285+
std::string namespace_; ///< ROS namespace set_camera_info service
275286
CameraInfo cam_info_; ///< current CameraInfo
276287
bool loaded_cam_info_; ///< cam_info_ load attempted
277288
}; // class CameraInfoManager

camera_info_manager/src/camera_info_manager.cpp

Lines changed: 13 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -69,38 +69,45 @@ const std::string
6969
* subordinate names, like "left/camera" and "right/camera".
7070
* @param cname default camera name
7171
* @param url default Uniform Resource Locator for loading and saving data.
72+
* @param ns namespace for the set_camera_info service. If not specified,
73+
* the service name will be "~/set_camera_info".
7274
*/
7375
CameraInfoManager::CameraInfoManager(
7476
rclcpp::Node * node, const std::string & cname,
75-
const std::string & url)
77+
const std::string & url, const std::string & ns)
7678
: CameraInfoManager(node->get_node_base_interface(),
77-
node->get_node_services_interface(), node->get_node_logging_interface(), cname, url)
79+
node->get_node_services_interface(), node->get_node_logging_interface(), cname, url,
80+
rmw_qos_profile_default, ns)
7881
{
7982
}
8083

8184
CameraInfoManager::CameraInfoManager(
8285
rclcpp_lifecycle::LifecycleNode * node,
83-
const std::string & cname, const std::string & url)
86+
const std::string & cname, const std::string & url,
87+
const std::string & ns)
8488
: CameraInfoManager(node->get_node_base_interface(),
85-
node->get_node_services_interface(), node->get_node_logging_interface(), cname, url)
89+
node->get_node_services_interface(), node->get_node_logging_interface(), cname, url,
90+
rmw_qos_profile_default, ns)
8691
{
8792
}
8893

8994
CameraInfoManager::CameraInfoManager(
9095
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
9196
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
9297
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logger_interface,
93-
const std::string & cname, const std::string & url, rmw_qos_profile_t custom_qos)
98+
const std::string & cname, const std::string & url,
99+
rmw_qos_profile_t custom_qos, const std::string & ns)
94100
: logger_(node_logger_interface->get_logger()),
95101
camera_name_(cname),
96102
url_(url),
103+
namespace_(ns),
97104
loaded_cam_info_(false)
98105
{
99106
using namespace std::placeholders;
100107

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

0 commit comments

Comments
 (0)