Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove 'node' namespace from rclcpp::Node #197

Merged
merged 1 commit into from
Nov 28, 2017
Merged
Show file tree
Hide file tree
Changes from all 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
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/timers/one_off_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ class OneOffTimerNode : public rclcpp::Node
{
public:
OneOffTimerNode()
: rclcpp::Node("one_off_timer"), count(0)
: Node("one_off_timer"), count(0)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is fine (correct) as a shortcut, but the existing code is also fine and a bit more explicit. I don't think you need to change this for this pr, but I wouldn't necessarily say we need to go out and do a similar change everywhere. Both are correct, and I think it's fine to leave it up to the author to decide which to use in the situation.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, no worries, I'll go easy on these ones 😄 thanks

{
periodic_timer = this->create_wall_timer(
2s,
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/timers/reuse_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ class OneOffTimerNode : public rclcpp::Node
{
public:
OneOffTimerNode()
: rclcpp::Node("reuse_timer"), count(0)
: Node("reuse_timer"), count(0)
{
one_off_timer = this->create_wall_timer(
1s,
Expand Down
2 changes: 1 addition & 1 deletion dummy_robot/dummy_map_server/src/dummy_map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);

auto node = rclcpp::node::Node::make_shared("dummy_map_server");
auto node = rclcpp::Node::make_shared("dummy_map_server");

rmw_qos_profile_t latched_qos = rmw_qos_profile_default;
latched_qos.depth = 1;
Expand Down
2 changes: 1 addition & 1 deletion dummy_robot/dummy_sensors/src/dummy_joint_states.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);

auto node = rclcpp::node::Node::make_shared("dummy_joint_states");
auto node = rclcpp::Node::make_shared("dummy_joint_states");

auto joint_state_pub = node->create_publisher<sensor_msgs::msg::JointState>(
"joint_states");
Expand Down
2 changes: 1 addition & 1 deletion dummy_robot/dummy_sensors/src/dummy_laser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);

auto node = rclcpp::node::Node::make_shared("dummy_laser");
auto node = rclcpp::Node::make_shared("dummy_laser");

auto laser_pub = node->create_publisher<sensor_msgs::msg::LaserScan>(
"scan");
Expand Down
2 changes: 1 addition & 1 deletion image_tools/src/cam2image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ int main(int argc, char * argv[])
}

// Initialize a ROS 2 node to publish images read from the OpenCV interface to the camera.
auto node = rclcpp::node::Node::make_shared("cam2image");
auto node = rclcpp::Node::make_shared("cam2image");

// Set the parameters of the quality of service profile. Initialize as the default profile
// and set the QoS parameters specified on the command line.
Expand Down
2 changes: 1 addition & 1 deletion image_tools/src/showimage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ int main(int argc, char * argv[])
}

// Initialize a ROS node.
auto node = rclcpp::node::Node::make_shared("showimage");
auto node = rclcpp::Node::make_shared("showimage");

// Set quality of service profile based on command line options.
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
Expand Down
4 changes: 2 additions & 2 deletions lifecycle/src/lifecycle_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,11 @@
* notifications about state changes of the node
* lc_talker
*/
class LifecycleListener : public rclcpp::node::Node
class LifecycleListener : public rclcpp::Node
{
public:
explicit LifecycleListener(const std::string & node_name)
: rclcpp::node::Node(node_name)
: Node(node_name)
{
// Data topic from the lc_talker node
sub_data_ = this->create_subscription<std_msgs::msg::String>("lifecycle_chatter",
Expand Down
4 changes: 2 additions & 2 deletions lifecycle/src/lifecycle_service_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,11 +59,11 @@ wait_for_result(
return status;
}

class LifecycleServiceClient : public rclcpp::node::Node
class LifecycleServiceClient : public rclcpp::Node
{
public:
explicit LifecycleServiceClient(const std::string & node_name)
: rclcpp::node::Node(node_name)
: Node(node_name)
{}

void
Expand Down
4 changes: 2 additions & 2 deletions pendulum_control/src/pendulum_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,11 +135,11 @@ int main(int argc, char * argv[])
std::make_shared<MessagePoolMemoryStrategy<pendulum_msgs::msg::JointCommand, 1>>();

// The controller node represents user code. This example implements a simple PID controller.
auto controller_node = rclcpp::node::Node::make_shared("pendulum_controller");
auto controller_node = rclcpp::Node::make_shared("pendulum_controller");

// The "motor" node simulates motors and sensors.
// It provides sensor data and changes the physical model based on the command.
auto motor_node = rclcpp::node::Node::make_shared("pendulum_motor");
auto motor_node = rclcpp::Node::make_shared("pendulum_motor");

// The quality of service profile is tuned for real-time performance.
// More QoS settings may be exposed by the rmw interface in the future to fulfill real-time
Expand Down
2 changes: 1 addition & 1 deletion pendulum_control/src/pendulum_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ int main(int argc, char * argv[])
setbuf(stdout, NULL);
rclcpp::init(argc, argv);

auto logger_node = rclcpp::node::Node::make_shared("pendulum_logger");
auto logger_node = rclcpp::Node::make_shared("pendulum_logger");
std::string filename = "pendulum_logger_results.csv";
std::ofstream fstream;
{
Expand Down
2 changes: 1 addition & 1 deletion pendulum_control/src/pendulum_teleop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ int main(int argc, char * argv[])
command = atof(argv[1]);
}

auto teleop_node = rclcpp::node::Node::make_shared("pendulum_teleop");
auto teleop_node = rclcpp::Node::make_shared("pendulum_teleop");

rmw_qos_profile_t qos_profile = rmw_qos_profile_default;
qos_profile.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
Expand Down