Skip to content
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion rviz2/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,11 @@ int main(int argc, char ** argv)
);

rviz_common::VisualizerApp vapp(
std::make_unique<rviz_common::ros_integration::RosClientAbstraction>());
std::make_unique<rviz_common::ros_integration::RosClientAbstraction>(
// In custom setups, this is the injection point for ROS node options
rclcpp::NodeOptions()
)
);
vapp.setApp(&qapp);
if (vapp.init(argc, argv)) {
return qapp.exec();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class RosClientAbstraction : public RosClientAbstractionIface
{
public:
RVIZ_COMMON_PUBLIC
RosClientAbstraction();
RosClientAbstraction(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

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

private:
std::shared_ptr<RosNodeAbstractionIface> rviz_ros_node_;
rclcpp::NodeOptions options_;
};

} // namespace ros_integration
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,9 @@ class RosNodeAbstraction : public RosNodeAbstractionIface
* \param node_name name of the node to create
*/
RVIZ_COMMON_PUBLIC
explicit RosNodeAbstraction(const std::string & node_name);
explicit RosNodeAbstraction(
const std::string & node_name,
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

/// Returns the name of the ros node
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,8 @@ namespace rviz_common
namespace ros_integration
{

RosClientAbstraction::RosClientAbstraction()
RosClientAbstraction::RosClientAbstraction(const rclcpp::NodeOptions & options)
: options_(options)
{}

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,10 @@ namespace rviz_common
namespace ros_integration
{

RosNodeAbstraction::RosNodeAbstraction(const std::string & node_name)
: raw_node_(rclcpp::Node::make_shared(node_name))
RosNodeAbstraction::RosNodeAbstraction(
const std::string & node_name,
const rclcpp::NodeOptions & options)
: raw_node_(rclcpp::Node::make_shared(node_name, options))
{}

std::string
Expand Down