Skip to content

Commit 69b2f92

Browse files
authored
Expose the possibility to create ROS node with custom NodeOptions (#1347)
Signed-off-by: Patrick Roncagliolo <[email protected]>
1 parent fbe9254 commit 69b2f92

File tree

5 files changed

+17
-7
lines changed

5 files changed

+17
-7
lines changed

rviz2/src/main.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,11 @@ int main(int argc, char ** argv)
8686
);
8787

8888
rviz_common::VisualizerApp vapp(
89-
std::make_unique<rviz_common::ros_integration::RosClientAbstraction>());
89+
std::make_unique<rviz_common::ros_integration::RosClientAbstraction>(
90+
// In custom setups, this is the injection point for ROS node options
91+
rclcpp::NodeOptions()
92+
)
93+
);
9094
vapp.setApp(&qapp);
9195
if (vapp.init(argc, argv)) {
9296
return qapp.exec();

rviz_common/include/rviz_common/ros_integration/ros_client_abstraction.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ class RosClientAbstraction : public RosClientAbstractionIface
4848
{
4949
public:
5050
RVIZ_COMMON_PUBLIC
51-
RosClientAbstraction();
51+
explicit RosClientAbstraction(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
5252

5353
// TODO(wjwwood): Figure out which exceptions can be raised and document them
5454
// consider consolidating all possible exceptions to a few
@@ -93,6 +93,7 @@ class RosClientAbstraction : public RosClientAbstractionIface
9393

9494
private:
9595
std::shared_ptr<RosNodeAbstractionIface> rviz_ros_node_;
96+
rclcpp::NodeOptions options_;
9697
};
9798

9899
} // namespace ros_integration

rviz_common/include/rviz_common/ros_integration/ros_node_abstraction.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,9 @@ class RosNodeAbstraction : public RosNodeAbstractionIface
6262
* \param node_name name of the node to create
6363
*/
6464
RVIZ_COMMON_PUBLIC
65-
explicit RosNodeAbstraction(const std::string & node_name);
65+
explicit RosNodeAbstraction(
66+
const std::string & node_name,
67+
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
6668

6769
/// Returns the name of the ros node
6870
/**

rviz_common/src/rviz_common/ros_integration/ros_client_abstraction.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,8 @@ namespace rviz_common
4444
namespace ros_integration
4545
{
4646

47-
RosClientAbstraction::RosClientAbstraction()
47+
RosClientAbstraction::RosClientAbstraction(const rclcpp::NodeOptions & options)
48+
: options_(options)
4849
{}
4950

5051
RosNodeAbstractionIface::WeakPtr
@@ -63,7 +64,7 @@ RosClientAbstraction::init(int argc, char ** argv, const std::string & name, boo
6364
// TODO(wjwwood): make a better exception type rather than using std::runtime_error.
6465
throw std::runtime_error("Node with name " + final_name + " already exists.");
6566
}
66-
rviz_ros_node_ = std::make_shared<RosNodeAbstraction>(final_name);
67+
rviz_ros_node_ = std::make_shared<RosNodeAbstraction>(final_name, options_);
6768
return rviz_ros_node_;
6869
}
6970

rviz_common/src/rviz_common/ros_integration/ros_node_abstraction.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,8 +44,10 @@ namespace rviz_common
4444
namespace ros_integration
4545
{
4646

47-
RosNodeAbstraction::RosNodeAbstraction(const std::string & node_name)
48-
: raw_node_(rclcpp::Node::make_shared(node_name))
47+
RosNodeAbstraction::RosNodeAbstraction(
48+
const std::string & node_name,
49+
const rclcpp::NodeOptions & options)
50+
: raw_node_(rclcpp::Node::make_shared(node_name, options))
4951
{}
5052

5153
std::string

0 commit comments

Comments
 (0)