fix: Fix identation 2 -> 4 spaces
This commit is contained in:
@@ -69,7 +69,7 @@ cpp_space_pointer_reference_alignment=left
|
||||
cpp_space_around_ternary_operator=insert
|
||||
cpp_wrap_preserve_blocks=one_liners
|
||||
indent_style = space
|
||||
indent_size = 2
|
||||
indent_size = 4
|
||||
charset = utf-8
|
||||
trim_trailing_whitespace = true
|
||||
insert_final_newline = true
|
||||
|
||||
@@ -14,40 +14,41 @@
|
||||
*/
|
||||
|
||||
#include <cstdlib>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
namespace lessons::one::clock {
|
||||
|
||||
class NodeClock : public rclcpp::Node {
|
||||
public:
|
||||
NodeClock()
|
||||
: Node("node_les1_clock")
|
||||
{
|
||||
timer_ = this->create_wall_timer(
|
||||
std::chrono::seconds(1),
|
||||
std::bind(&NodeClock::print_time, this)
|
||||
);
|
||||
}
|
||||
NodeClock()
|
||||
: Node("node_les1_clock")
|
||||
{
|
||||
timer_ = this->create_wall_timer(
|
||||
std::chrono::seconds(1),
|
||||
std::bind(&NodeClock::print_time, this)
|
||||
);
|
||||
}
|
||||
|
||||
void print_time() {
|
||||
auto now = clock_.now();
|
||||
RCLCPP_INFO(this->get_logger(), "Time: %.0f", now.seconds());
|
||||
}
|
||||
void print_time() {
|
||||
auto now = clock_.now();
|
||||
RCLCPP_INFO(this->get_logger(), "Time: %.0f", now.seconds());
|
||||
}
|
||||
|
||||
private:
|
||||
rclcpp::TimerBase::SharedPtr timer_;
|
||||
rclcpp::Clock clock_;
|
||||
rclcpp::TimerBase::SharedPtr timer_;
|
||||
rclcpp::Clock clock_;
|
||||
};
|
||||
|
||||
} // namespace lessons::one::clock
|
||||
|
||||
int main(int argc,char *argv[]) {
|
||||
rclcpp::init(argc,argv);
|
||||
rclcpp::init(argc,argv);
|
||||
|
||||
auto node = std::make_shared<lessons::one::clock::NodeClock>();
|
||||
auto node = std::make_shared<lessons::one::clock::NodeClock>();
|
||||
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -81,12 +81,12 @@ private:
|
||||
} // namespace lessons::one::pubsub
|
||||
|
||||
int main(int argc,char *argv[]) {
|
||||
rclcpp::init(argc,argv);
|
||||
rclcpp::init(argc,argv);
|
||||
|
||||
auto node = std::make_shared<lessons::one::pubsub::NodePublisher>();
|
||||
auto node = std::make_shared<lessons::one::pubsub::NodePublisher>();
|
||||
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -23,45 +23,46 @@ public:
|
||||
NodeLes1Subscriber()
|
||||
: Node("node_les1_subscriber")
|
||||
{
|
||||
subscriber_location_ =
|
||||
this->create_subscription<geometry_msgs::msg::Point>(
|
||||
"location", 10,
|
||||
std::bind(&NodeLes1Subscriber::sub_callback_location, this, _1)
|
||||
subscriber_location_ =
|
||||
this->create_subscription<geometry_msgs::msg::Point>(
|
||||
"location", 10,
|
||||
std::bind(&NodeLes1Subscriber::sub_callback_location, this, _1)
|
||||
);
|
||||
|
||||
subscriber_hw_status_ =
|
||||
this->create_subscription<les_interface::msg::HardwareStatus>(
|
||||
"hardware_status", 10,
|
||||
std::bind(&NodeLes1Subscriber::sub_callback_hw_status, this, _1)
|
||||
);
|
||||
}
|
||||
|
||||
void sub_callback_location(const geometry_msgs::msg::Point::SharedPtr msg) {
|
||||
RCLCPP_INFO(this->get_logger(),
|
||||
"Received: x=%.2f, y=%.2f, z=%.2f", msg->x, msg->y, msg->z
|
||||
);
|
||||
}
|
||||
|
||||
subscriber_hw_status_ =
|
||||
this->create_subscription<les_interface::msg::HardwareStatus>(
|
||||
"hardware_status", 10,
|
||||
std::bind(&NodeLes1Subscriber::sub_callback_hw_status, this, _1)
|
||||
void sub_callback_hw_status(const les_interface::msg::HardwareStatus::SharedPtr msg) {
|
||||
RCLCPP_INFO(this->get_logger(),
|
||||
"Received HW status: version=%ld, temp=%.2f, motors_ready=%s, msg=%s",
|
||||
msg->version, msg->temperature,
|
||||
msg->are_motors_ready ? "true" : "false",
|
||||
msg->debug_message.c_str()
|
||||
);
|
||||
}
|
||||
|
||||
void sub_callback_location(const geometry_msgs::msg::Point::SharedPtr msg) {
|
||||
RCLCPP_INFO(this->get_logger(),
|
||||
"Received: x=%.2f, y=%.2f, z=%.2f", msg->x, msg->y, msg->z
|
||||
);
|
||||
}
|
||||
|
||||
void sub_callback_hw_status(const les_interface::msg::HardwareStatus::SharedPtr msg) {
|
||||
RCLCPP_INFO(this->get_logger(),
|
||||
"Received HW status: version=%ld, temp=%.2f, motors_ready=%s, msg=%s",
|
||||
msg->version, msg->temperature,
|
||||
msg->are_motors_ready ? "true" : "false",
|
||||
msg->debug_message.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
rclcpp::Subscription<geometry_msgs::msg::Point>::SharedPtr subscriber_location_;
|
||||
rclcpp::Subscription<les_interface::msg::HardwareStatus>::SharedPtr subscriber_hw_status_;
|
||||
rclcpp::Subscription<geometry_msgs::msg::Point>::SharedPtr subscriber_location_;
|
||||
rclcpp::Subscription<les_interface::msg::HardwareStatus>::SharedPtr subscriber_hw_status_;
|
||||
};
|
||||
|
||||
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<NodeLes1Subscriber>();
|
||||
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -21,51 +21,59 @@ namespace lessons::two::service {
|
||||
|
||||
class NodeClient : public rclcpp::Node {
|
||||
public:
|
||||
NodeClient()
|
||||
: Node("node_les2_service_client")
|
||||
{
|
||||
client_ = this->create_client<ServiceVec>("vec_service_server");
|
||||
timer_ = this->create_wall_timer(
|
||||
seconds(3),
|
||||
std::bind(&NodeClient::send_request, this)
|
||||
);
|
||||
}
|
||||
NodeClient()
|
||||
: Node("node_les2_service_client")
|
||||
{
|
||||
client_ = this->create_client<ServiceVec>("vec_service_server");
|
||||
timer_ = this->create_wall_timer(
|
||||
seconds(3),
|
||||
std::bind(&NodeClient::send_request, this)
|
||||
);
|
||||
}
|
||||
|
||||
private:
|
||||
void send_request() {
|
||||
if (!client_->wait_for_service(seconds(1))) {
|
||||
RCLCPP_WARN(this->get_logger(), "Service not available");
|
||||
return;
|
||||
}
|
||||
void send_request() {
|
||||
if (!client_->wait_for_service(seconds(1))) {
|
||||
RCLCPP_WARN(this->get_logger(), "Service not available");
|
||||
return;
|
||||
}
|
||||
|
||||
auto request = std::make_shared<ServiceVec::Request>();
|
||||
request->x = rand() % 100;
|
||||
request->y = rand() % 100;
|
||||
request->z = rand() % 100;
|
||||
auto request = std::make_shared<ServiceVec::Request>();
|
||||
request->x = rand() % 100;
|
||||
request->y = rand() % 100;
|
||||
request->z = rand() % 100;
|
||||
|
||||
auto future = client_->async_send_request(request,
|
||||
std::bind(&NodeClient::handle_response, this, std::placeholders::_1)
|
||||
);
|
||||
}
|
||||
auto future = client_->async_send_request(request);
|
||||
auto result = rclcpp::spin_until_future_complete(this->shared_from_this(), future, std::chrono::seconds(2));
|
||||
|
||||
void handle_response(rclcpp::Client<ServiceVec>::SharedFuture future) {
|
||||
auto response = future.get();
|
||||
RCLCPP_INFO(this->get_logger(), "Received vec len: %.6lf", response->vec_len);
|
||||
}
|
||||
if (result == rclcpp::FutureReturnCode::SUCCESS) {
|
||||
auto response = future.get();
|
||||
RCLCPP_INFO(this->get_logger(), "Received vec len: %.6lf", response->vec_len);
|
||||
} else if (result == rclcpp::FutureReturnCode::TIMEOUT) {
|
||||
RCLCPP_WARN(this->get_logger(), "Service call timed out");
|
||||
} else {
|
||||
RCLCPP_ERROR(this->get_logger(), "Service call failed");
|
||||
}
|
||||
}
|
||||
|
||||
rclcpp::Client<ServiceVec>::SharedPtr client_;
|
||||
rclcpp::TimerBase::SharedPtr timer_;
|
||||
void handle_response(rclcpp::Client<ServiceVec>::SharedFuture future) {
|
||||
auto response = future.get();
|
||||
RCLCPP_INFO(this->get_logger(), "Received vec len: %.6lf", response->vec_len);
|
||||
}
|
||||
|
||||
rclcpp::Client<ServiceVec>::SharedPtr client_;
|
||||
rclcpp::TimerBase::SharedPtr timer_;
|
||||
};
|
||||
|
||||
} // namespace lessons::two::service
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
srand(time(NULL));
|
||||
rclcpp::init(argc, argv);
|
||||
srand(time(NULL));
|
||||
rclcpp::init(argc, argv);
|
||||
|
||||
auto node = std::make_shared<lessons::two::service::NodeClient>();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
auto node = std::make_shared<lessons::two::service::NodeClient>();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -21,49 +21,49 @@ namespace lessons::two::service {
|
||||
|
||||
class NodeServer : public rclcpp::Node {
|
||||
public:
|
||||
NodeServer()
|
||||
: Node("node_les2_service_server")
|
||||
{
|
||||
vec_service_server_ =
|
||||
this->create_service<ServiceVec>(
|
||||
"vec_service_server",
|
||||
std::bind(
|
||||
&NodeServer::callback_service,
|
||||
this,
|
||||
std::placeholders::_1,
|
||||
std::placeholders::_2
|
||||
)
|
||||
);
|
||||
NodeServer()
|
||||
: Node("node_les2_service_server")
|
||||
{
|
||||
vec_service_server_ =
|
||||
this->create_service<ServiceVec>(
|
||||
"vec_service_server",
|
||||
std::bind(
|
||||
&NodeServer::callback_service,
|
||||
this,
|
||||
std::placeholders::_1,
|
||||
std::placeholders::_2
|
||||
)
|
||||
);
|
||||
|
||||
RCLCPP_INFO(this->get_logger(), "Service Server started");
|
||||
}
|
||||
RCLCPP_INFO(this->get_logger(), "Service Server started");
|
||||
}
|
||||
|
||||
void callback_service(
|
||||
const ServiceVec::Request::SharedPtr request,
|
||||
ServiceVec::Response::SharedPtr response
|
||||
) {
|
||||
response->vec_len = sqrt(
|
||||
pow(request->x, 2) + pow(request->y, 2) + pow(request->z, 2)
|
||||
);
|
||||
void callback_service(
|
||||
const ServiceVec::Request::SharedPtr request,
|
||||
ServiceVec::Response::SharedPtr response
|
||||
) {
|
||||
response->vec_len = sqrt(
|
||||
pow(request->x, 2) + pow(request->y, 2) + pow(request->z, 2)
|
||||
);
|
||||
|
||||
RCLCPP_INFO(this->get_logger(),
|
||||
"sqrt(pow(%.6lf), pow(%.6lf), pow(%.6lf))=%.6lf",
|
||||
request->x, request->y, request->z, response->vec_len
|
||||
);
|
||||
}
|
||||
RCLCPP_INFO(this->get_logger(),
|
||||
"sqrt(pow(%.6lf), pow(%.6lf), pow(%.6lf))=%.6lf",
|
||||
request->x, request->y, request->z, response->vec_len
|
||||
);
|
||||
}
|
||||
|
||||
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[]) {
|
||||
rclcpp::init(argc, argv);
|
||||
rclcpp::init(argc, argv);
|
||||
|
||||
auto node = std::make_shared<lessons::two::service::NodeServer>();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
auto node = std::make_shared<lessons::two::service::NodeServer>();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -1,5 +1,9 @@
|
||||
/* node_template.cpp
|
||||
* Basic node template for ROS2
|
||||
* Action server node template for ROS2
|
||||
*
|
||||
* Node description:
|
||||
* Template action server that demonstrates action server implementation
|
||||
* with goal handling, feedback publishing, and cancellation support
|
||||
*
|
||||
* Reviewed by: <x>
|
||||
* Changelog:
|
||||
@@ -7,16 +11,17 @@
|
||||
*/
|
||||
|
||||
#include <cstdlib>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
namespace lessons::zero::template {
|
||||
|
||||
class NodeTemplate : public rclcpp::Node {
|
||||
public:
|
||||
NodeTemplate()
|
||||
: Node("node_template")
|
||||
{
|
||||
}
|
||||
NodeTemplate()
|
||||
: Node("node_template")
|
||||
{
|
||||
}
|
||||
|
||||
private:
|
||||
};
|
||||
@@ -24,12 +29,12 @@ private:
|
||||
} // namespace lessons::zero::template
|
||||
|
||||
int main(int argc,char *argv[]) {
|
||||
rclcpp::init(argc,argv);
|
||||
rclcpp::init(argc,argv);
|
||||
|
||||
auto node = std::make_shared<lessons::zero::template::NodeTemplate>();
|
||||
auto node = std::make_shared<lessons::zero::template::NodeTemplate>();
|
||||
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user