@@ -69,38 +69,45 @@ const std::string
69
69
* subordinate names, like "left/camera" and "right/camera".
70
70
* @param cname default camera name
71
71
* @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".
72
74
*/
73
75
CameraInfoManager::CameraInfoManager (
74
76
rclcpp::Node * node, const std::string & cname,
75
- const std::string & url)
77
+ const std::string & url, const std::string & ns )
76
78
: 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)
78
81
{
79
82
}
80
83
81
84
CameraInfoManager::CameraInfoManager (
82
85
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)
84
88
: 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)
86
91
{
87
92
}
88
93
89
94
CameraInfoManager::CameraInfoManager (
90
95
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
91
96
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
92
97
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)
94
100
: logger_(node_logger_interface->get_logger ()),
95
101
camera_name_(cname),
96
102
url_(url),
103
+ namespace_(ns),
97
104
loaded_cam_info_(false )
98
105
{
99
106
using namespace std ::placeholders;
100
107
101
108
// register callback for camera calibration service request
102
109
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" ,
104
111
std::bind (&CameraInfoManager::setCameraInfoService, this , _1, _2), custom_qos, nullptr );
105
112
}
106
113
0 commit comments