fix: Move into namespaces

This commit is contained in:
2025-09-11 12:20:15 +02:00
parent de535b2ee2
commit cce36d567f
6 changed files with 71 additions and 36 deletions

View File

@@ -8,37 +8,43 @@
* [07-09-2025] Wessel T: * [07-09-2025] Wessel T:
* - Rename {les1.cpp -> les1/clock.cpp} * - Rename {les1.cpp -> les1/clock.cpp}
* - Update node names to be in line with other files * - Update node names to be in line with other files
* [11-09-2025] Wessel T: Remove unused imports * [11-09-2025] Wessel T:
* - Remove unused imports
* - Wrap into namespace
*/ */
#include <cstdlib> #include <cstdlib>
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
class NodeLes1Clock : public rclcpp::Node { namespace lessons::one::clock {
class NodeClock : public rclcpp::Node {
public: public:
NodeLes1Clock() NodeClock()
: Node("node_les1_clock") : Node("node_les1_clock")
{ {
timer_ = this->create_wall_timer( timer_ = this->create_wall_timer(
std::chrono::seconds(1), std::chrono::seconds(1),
std::bind(&NodeLes1Clock::print_time, this) std::bind(&NodeClock::print_time, this)
); );
} }
void print_time() { void print_time() {
auto now = clock_.now(); auto now = clock_.now();
RCLCPP_INFO(this->get_logger(), "Time: %.0f", now.seconds()); RCLCPP_INFO(this->get_logger(), "Time: %.0f", now.seconds());
} }
private: private:
rclcpp::TimerBase::SharedPtr timer_; rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Clock clock_; rclcpp::Clock clock_;
}; };
} // namespace lessons::one::clock
int main(int argc,char *argv[]) { int main(int argc,char *argv[]) {
rclcpp::init(argc,argv); rclcpp::init(argc,argv);
auto node = std::make_shared<NodeLes1Clock>(); auto node = std::make_shared<lessons::one::clock::NodeClock>();
rclcpp::spin(node); rclcpp::spin(node);
rclcpp::shutdown(); rclcpp::shutdown();

View File

@@ -6,7 +6,9 @@
* Changelog: * Changelog:
* [04-09-2025] Wessel T: * [04-09-2025] Wessel T:
* - Implement template * - Implement template
* [11-09-2025] Wessel T: Remove unused imports * [11-09-2025] Wessel T:
* - Remove unused imports
* - Wrap into namespace
*/ */
#include <cstdlib> #include <cstdlib>
@@ -16,9 +18,11 @@
#include "geometry_msgs/msg/point.hpp" // Point for x, y, z coordinates #include "geometry_msgs/msg/point.hpp" // Point for x, y, z coordinates
#include "les_interface/msg/hardware_status.hpp" // Custom HW status message #include "les_interface/msg/hardware_status.hpp" // Custom HW status message
class NodeLes1Publisher : public rclcpp::Node { namespace lessons::one::pubsub {
class NodePublisher : public rclcpp::Node {
public: public:
NodeLes1Publisher() NodePublisher()
: Node("node_les1_publisher") : Node("node_les1_publisher")
{ {
publisher_location_ = publisher_location_ =
@@ -29,12 +33,12 @@ public:
timer_location_ = this->create_wall_timer( timer_location_ = this->create_wall_timer(
std::chrono::seconds(2), std::chrono::seconds(2),
std::bind(&NodeLes1Publisher::timer_location_function, this) std::bind(&NodePublisher::timer_location_function, this)
); );
timer_hw_status_ = this->create_wall_timer( timer_hw_status_ = this->create_wall_timer(
std::chrono::seconds(2), std::chrono::seconds(2),
std::bind(&NodeLes1Publisher::timer_hw_status_function, this) std::bind(&NodePublisher::timer_hw_status_function, this)
); );
} }
@@ -74,10 +78,12 @@ private:
rclcpp::TimerBase::SharedPtr timer_hw_status_; rclcpp::TimerBase::SharedPtr timer_hw_status_;
}; };
} // namespace lessons::one::pubsub
int main(int argc,char *argv[]) { int main(int argc,char *argv[]) {
rclcpp::init(argc,argv); rclcpp::init(argc,argv);
auto node = std::make_shared<NodeLes1Publisher>(); auto node = std::make_shared<lessons::one::pubsub::NodePublisher>();
rclcpp::spin(node); rclcpp::spin(node);
rclcpp::shutdown(); rclcpp::shutdown();

View File

@@ -5,7 +5,8 @@
* Reviewed by: <x> * Reviewed by: <x>
* Changelog: * Changelog:
* [04-09-2025] Wessel T: * [04-09-2025] Wessel T:
* - Implement template * - Implement template
* - Wrap into namespace
*/ */
#include <cstdlib> #include <cstdlib>
@@ -17,22 +18,25 @@
using namespace std::placeholders; using namespace std::placeholders;
class NodeLes1Subscriber : public rclcpp::Node { namespace lessons::one::pubsub {
class NodeSubscriber : public rclcpp::Node {
public: public:
NodeLes1Subscriber() NodeSubscriber()
: Node("node_les1_subscriber") : Node("node_les1_subscriber")
{ {
subscriber_location_ = subscriber_location_ =
this->create_subscription<geometry_msgs::msg::Point>( this->create_subscription<geometry_msgs::msg::Point>(
"location", 10, "location", 10,
std::bind(&NodeLes1Subscriber::sub_callback_location, this, _1) std::bind(&NodeSubscriber::sub_callback_location, this, _1)
); );
subscriber_hw_status_ = subscriber_hw_status_ =
this->create_subscription<les_interface::msg::HardwareStatus>( this->create_subscription<les_interface::msg::HardwareStatus>(
"hardware_status", 10, "hardware_status", 10,
std::bind(&NodeLes1Subscriber::sub_callback_hw_status, this, _1) std::bind(&NodeSubscriber::sub_callback_hw_status, this, _1)
); );
} }
@@ -55,10 +59,12 @@ private:
rclcpp::Subscription<les_interface::msg::HardwareStatus>::SharedPtr subscriber_hw_status_; rclcpp::Subscription<les_interface::msg::HardwareStatus>::SharedPtr subscriber_hw_status_;
}; };
} // namespace lessons::one::pubsub
int main(int argc,char *argv[]) { int main(int argc,char *argv[]) {
rclcpp::init(argc,argv); rclcpp::init(argc,argv);
auto node = std::make_shared<NodeLes1Subscriber>(); auto node = std::make_shared<lessons::one::pubsub::NodeSubscriber>();
rclcpp::spin(node); rclcpp::spin(node);
rclcpp::shutdown(); rclcpp::shutdown();

View File

@@ -4,7 +4,9 @@
* Reviewed by: <x> * Reviewed by: <x>
* Changelog: * Changelog:
* [04-09-2025] Wessel T: Implement template * [04-09-2025] Wessel T: Implement template
* [11-09-2025] Wessel T: (BASE) Working service client * [11-09-2025] Wessel T:
* - (BASE) Working service client
* - Wrap into namespace
*/ */
#include <chrono> #include <chrono>
@@ -15,15 +17,17 @@
using namespace std::chrono; using namespace std::chrono;
using les_interface::srv::ServiceVec; using les_interface::srv::ServiceVec;
class NodeLes2ServiceClient : public rclcpp::Node { namespace lessons::two::service {
class NodeClient : public rclcpp::Node {
public: public:
NodeLes2ServiceClient() NodeClient()
: Node("node_les2_service_client") : Node("node_les2_service_client")
{ {
client_ = this->create_client<ServiceVec>("vec_service_server"); client_ = this->create_client<ServiceVec>("vec_service_server");
timer_ = this->create_wall_timer( timer_ = this->create_wall_timer(
seconds(3), seconds(3),
std::bind(&NodeLes2ServiceClient::send_request, this) std::bind(&NodeClient::send_request, this)
); );
} }
@@ -40,7 +44,7 @@ private:
request->z = rand() % 100; request->z = rand() % 100;
auto future = client_->async_send_request(request, auto future = client_->async_send_request(request,
std::bind(&NodeLes2ServiceClient::handle_response, this, std::placeholders::_1) std::bind(&NodeClient::handle_response, this, std::placeholders::_1)
); );
} }
@@ -53,13 +57,15 @@ private:
rclcpp::TimerBase::SharedPtr timer_; rclcpp::TimerBase::SharedPtr timer_;
}; };
int main(int argc, char **argv) { } // namespace lessons::two::service
srand(time(NULL));
rclcpp::init(argc, argv);
auto node = std::make_shared<NodeLes2ServiceClient>(); int main(int argc, char **argv) {
srand(time(NULL));
rclcpp::init(argc, argv);
auto node = std::make_shared<lessons::two::service::NodeClient>();
rclcpp::spin(node); rclcpp::spin(node);
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View File

@@ -4,7 +4,9 @@
* Reviewed by: <x> * Reviewed by: <x>
* Changelog: * Changelog:
* [04-09-2025] Wessel T: Implement template * [04-09-2025] Wessel T: Implement template
* [11-09-2025] Wessel T: (BASE) Working service client * [11-09-2025] Wessel T:
* - (BASE) Working service client
* - Wrap into namespace
*/ */
#include <cstdlib> #include <cstdlib>
@@ -14,16 +16,19 @@
using les_interface::srv::ServiceVec; using les_interface::srv::ServiceVec;
class NodeLes2ServiceServer : public rclcpp::Node {
namespace lessons::two::service {
class NodeServer : public rclcpp::Node {
public: public:
NodeLes2ServiceServer() NodeServer()
: Node("node_les2_service_server") : Node("node_les2_service_server")
{ {
vec_service_server_ = vec_service_server_ =
this->create_service<ServiceVec>( this->create_service<ServiceVec>(
"vec_service_server", "vec_service_server",
std::bind( std::bind(
&NodeLes2ServiceServer::callback_service, &NodeServer::callback_service,
this, this,
std::placeholders::_1, std::placeholders::_1,
std::placeholders::_2 std::placeholders::_2
@@ -51,10 +56,12 @@ private:
rclcpp::Service<ServiceVec>::SharedPtr vec_service_server_; rclcpp::Service<ServiceVec>::SharedPtr vec_service_server_;
}; };
} // namespace lessons::two::service
int main(int argc, char *argv[]) { int main(int argc, char *argv[]) {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
auto node = std::make_shared<NodeLes2ServiceServer>(); auto node = std::make_shared<lessons::two::service::NodeServer>();
rclcpp::spin(node); rclcpp::spin(node);
rclcpp::shutdown(); rclcpp::shutdown();

View File

@@ -9,6 +9,8 @@
#include <cstdlib> #include <cstdlib>
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
namespace lessons::zero::template {
class NodeTemplate : public rclcpp::Node { class NodeTemplate : public rclcpp::Node {
public: public:
NodeTemplate() NodeTemplate()
@@ -19,10 +21,12 @@ public:
private: private:
}; };
} // namespace lessons::zero::template
int main(int argc,char *argv[]) { int main(int argc,char *argv[]) {
rclcpp::init(argc,argv); rclcpp::init(argc,argv);
auto node = std::make_shared<NodeTemplate>(); auto node = std::make_shared<lessons::zero::template::NodeTemplate>();
rclcpp::spin(node); rclcpp::spin(node);
rclcpp::shutdown(); rclcpp::shutdown();