Skip to content

Commit

Permalink
support addition of node namespace in rclcpp API (#121)
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood authored Apr 8, 2017
1 parent 9c2006d commit 1ddd21e
Show file tree
Hide file tree
Showing 7 changed files with 9 additions and 9 deletions.
4 changes: 2 additions & 2 deletions demo_nodes_cpp/src/topics/allocator_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,10 +147,10 @@ int main(int argc, char ** argv)
std::make_shared<rclcpp::intra_process_manager::IntraProcessManagerImpl<MyAllocator<>>>();
// Constructs the intra-process manager with a custom allocator.
context->get_sub_context<rclcpp::intra_process_manager::IntraProcessManager>(ipm_state);
node = rclcpp::Node::make_shared("allocator_tutorial", true);
node = rclcpp::Node::make_shared("allocator_tutorial", "", true);
} else {
printf("Intra-process pipeline is OFF.\n");
node = rclcpp::Node::make_shared("allocator_tutorial", false);
node = rclcpp::Node::make_shared("allocator_tutorial", "", false);
}

uint32_t counter = 0;
Expand Down
2 changes: 1 addition & 1 deletion intra_process_demo/src/cyclic_pipeline/cyclic_pipeline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ using namespace std::chrono_literals;
struct IncrementerPipe : public rclcpp::Node
{
IncrementerPipe(const std::string & name, const std::string & in, const std::string & out)
: Node(name, true)
: Node(name, "", true)
{
// Create a publisher on the output topic.
pub = this->create_publisher<std_msgs::msg::Int32>(out, rmw_qos_profile_default);
Expand Down
2 changes: 1 addition & 1 deletion intra_process_demo/src/image_pipeline/camera_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class CameraNode : public rclcpp::Node
public:
CameraNode(const std::string & output, const std::string & node_name = "camera_node",
int device = 0, int width = 320, int height = 240)
: Node(node_name, true), canceled_(false)
: Node(node_name, "", true), canceled_(false)
{
// Initialize OpenCV
cap_.open(device);
Expand Down
2 changes: 1 addition & 1 deletion intra_process_demo/src/image_pipeline/image_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class ImageViewNode : public rclcpp::Node
public:
explicit ImageViewNode(
const std::string & input, const std::string & node_name = "image_view_node")
: Node(node_name, true)
: Node(node_name, "", true)
{
// Create a subscription on the input topic.
sub_ = this->create_subscription<sensor_msgs::msg::Image>(
Expand Down
2 changes: 1 addition & 1 deletion intra_process_demo/src/image_pipeline/watermark_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class WatermarkNode : public rclcpp::Node
WatermarkNode(
const std::string & input, const std::string & output, const std::string & text,
const std::string & node_name = "watermark_node")
: Node(node_name, true)
: Node(node_name, "", true)
{
auto qos = rmw_qos_profile_sensor_data;
// Create a publisher on the input topic.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ using namespace std::chrono_literals;
struct Producer : public rclcpp::Node
{
Producer(const std::string & name, const std::string & output)
: Node(name, true)
: Node(name, "", true)
{
// Create a publisher on the output topic.
pub_ = this->create_publisher<std_msgs::msg::Int32>(output, rmw_qos_profile_default);
Expand Down Expand Up @@ -57,7 +57,7 @@ struct Producer : public rclcpp::Node
struct Consumer : public rclcpp::Node
{
Consumer(const std::string & name, const std::string & input)
: Node(name, true)
: Node(name, "", true)
{
// Create a subscription on the input topic which prints on receipt of new messages.
sub_ = this->create_subscription<std_msgs::msg::Int32>(
Expand Down
2 changes: 1 addition & 1 deletion lifecycle/src/lifecycle_talker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode
* arguments a regular node.
*/
explicit LifecycleTalker(const std::string & node_name, bool intra_process_comms = false)
: rclcpp_lifecycle::LifecycleNode(node_name, intra_process_comms)
: rclcpp_lifecycle::LifecycleNode(node_name, "", intra_process_comms)
{}

/// Callback for walltimer in order to publish the message.
Expand Down

0 comments on commit 1ddd21e

Please sign in to comment.