mirror of
https://github.com/modelec/modelec-marcel-ROS.git
synced 2026-01-18 16:47:43 +01:00
async do not work for the moment
This commit is contained in:
@@ -127,6 +127,7 @@ install(TARGETS
|
||||
solenoid_controller
|
||||
arm_controller
|
||||
button_gpio_controller
|
||||
pcb_alim_interface
|
||||
DESTINATION lib/${PROJECT_NAME}
|
||||
)
|
||||
|
||||
|
||||
@@ -4,6 +4,7 @@
|
||||
#include <boost/asio.hpp>
|
||||
#include <std_msgs/msg/string.hpp>
|
||||
#include <modelec_interface/srv/add_serial_listener.hpp>
|
||||
#include <thread>
|
||||
|
||||
#define MAX_MESSAGE_LEN 1048
|
||||
#define READ_REFRESH_RATE 100 //ms
|
||||
@@ -27,7 +28,7 @@ private:
|
||||
int bauds_;
|
||||
std::string serial_port_;
|
||||
int max_message_len_;
|
||||
boost::asio::streambuf read_buffer_;
|
||||
boost::asio::streambuf read_buf_;
|
||||
boost::asio::io_service& io_;
|
||||
|
||||
public:
|
||||
@@ -41,8 +42,8 @@ private:
|
||||
|
||||
void SetMaxMessageLen(int max_message_len) { max_message_len_ = max_message_len; }
|
||||
bool IsOk() const { return status_; }
|
||||
void asyncRead();
|
||||
void asyncWrite(const std::string& data);
|
||||
void read();
|
||||
void write(const std::string& data);
|
||||
};
|
||||
|
||||
std::map<std::string, std::shared_ptr<SerialListener>> serial_listeners;
|
||||
|
||||
11
src/modelec/launch/test.modelec.launch.yml
Normal file
11
src/modelec/launch/test.modelec.launch.yml
Normal file
@@ -0,0 +1,11 @@
|
||||
launch:
|
||||
|
||||
- node:
|
||||
pkg: modelec
|
||||
exec: "serial_listener"
|
||||
name: "serial_listener"
|
||||
|
||||
- node:
|
||||
pkg: 'modelec'
|
||||
exec: 'usb_arduino_logic_processor'
|
||||
name: 'usb_arduino_logic_processor'
|
||||
@@ -5,7 +5,8 @@ namespace Modelec {
|
||||
add_serial_listener_service_ = create_service<modelec_interface::srv::AddSerialListener>("add_serial_listener", std::bind(&MultipleSerialListener::add_serial_listener, this, std::placeholders::_1, std::placeholders::_2));
|
||||
timer = create_wall_timer(std::chrono::milliseconds(READ_REFRESH_RATE), [this]() {
|
||||
for (auto &listener : serial_listeners) {
|
||||
listener.second->asyncRead();
|
||||
if (listener.second->IsOk())
|
||||
listener.second->read();
|
||||
}
|
||||
});
|
||||
|
||||
@@ -39,7 +40,7 @@ namespace Modelec {
|
||||
listener->publisher_ = create_publisher<std_msgs::msg::String>("raw_data/" + listener->name_, 10);
|
||||
listener->subscriber_ = create_subscription<std_msgs::msg::String>(
|
||||
"send_to_serial/" + listener->name_, 10, [listener](std_msgs::msg::String::SharedPtr msg) {
|
||||
listener->asyncWrite(msg->data);
|
||||
listener->write(msg->data);
|
||||
});
|
||||
|
||||
serial_listeners.insert({request->name, listener});
|
||||
@@ -67,12 +68,11 @@ namespace Modelec {
|
||||
listener.second->SetMaxMessageLen(get_parameter("max_message_len").as_int());
|
||||
}
|
||||
|
||||
// change the timer refresh rate
|
||||
read_refresh_rate_ = get_parameter("read_refresh_rate").as_int();
|
||||
timer->cancel();
|
||||
timer = create_wall_timer(std::chrono::milliseconds(read_refresh_rate_), [this]() {
|
||||
for (auto &listener : serial_listeners) {
|
||||
listener.second->asyncRead();
|
||||
listener.second->read();
|
||||
}
|
||||
});
|
||||
}
|
||||
@@ -89,37 +89,34 @@ namespace Modelec {
|
||||
status_ = false;
|
||||
return;
|
||||
}
|
||||
asyncRead(); // Start asynchronous reading
|
||||
}
|
||||
|
||||
void MultipleSerialListener::SerialListener::asyncRead() {
|
||||
void MultipleSerialListener::SerialListener::read() {
|
||||
if (!status_) return;
|
||||
|
||||
boost::asio::async_read_until(port_, read_buffer_, '\n',
|
||||
[this](boost::system::error_code ec, std::size_t) {
|
||||
if (!ec) {
|
||||
std::istream is(&read_buffer_);
|
||||
std::string data;
|
||||
std::getline(is, data);
|
||||
std_msgs::msg::String msg;
|
||||
msg.data = data;
|
||||
publisher_->publish(msg);
|
||||
} else {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("SerialListener"), "Read error: %s", ec.message().c_str());
|
||||
}
|
||||
asyncRead(); // Continue reading asynchronously
|
||||
});
|
||||
std::vector<char> data(max_message_len_);
|
||||
try {
|
||||
// Attempt to read data from the serial port
|
||||
|
||||
size_t len = port_.read_some(boost::asio::buffer(data.data(), max_message_len_));
|
||||
if (len > 0) {
|
||||
// Prepare and publish the message
|
||||
auto msg = std_msgs::msg::String();
|
||||
msg.data = std::string(data.begin(), data.begin() + len);
|
||||
publisher_->publish(msg);
|
||||
}
|
||||
} catch (boost::system::system_error &e) {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("SerialListener"), "Read error: %s", e.what());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void MultipleSerialListener::SerialListener::asyncWrite(const std::string& data) {
|
||||
if (!status_) return;
|
||||
|
||||
boost::asio::async_write(port_, boost::asio::buffer(data),
|
||||
[](boost::system::error_code ec, std::size_t) {
|
||||
if (ec) {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("SerialListener"), "Write error: %s", ec.message().c_str());
|
||||
}
|
||||
});
|
||||
void MultipleSerialListener::SerialListener::write(const std::string& data) {
|
||||
try {
|
||||
boost::asio::write(port_, boost::asio::buffer(data));
|
||||
} catch (boost::system::system_error &e) {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("SerialListener"), "Write error: %s", e.what());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -11,7 +11,7 @@ LogicProcessor::LogicProcessor() : Node("usb_logic_processor") {
|
||||
auto request = std::make_shared<modelec_interface::srv::AddSerialListener::Request>();
|
||||
request->name = "arduino";
|
||||
request->bauds = 115200;
|
||||
request->serial_port = "/dev/ttyACM0";
|
||||
request->serial_port = "/dev/pts/6";
|
||||
auto client = this->create_client<modelec_interface::srv::AddSerialListener>("add_serial_listener");
|
||||
while (!client->wait_for_service(std::chrono::seconds(1))) {
|
||||
if (!rclcpp::ok()) {
|
||||
@@ -22,24 +22,32 @@ LogicProcessor::LogicProcessor() : Node("usb_logic_processor") {
|
||||
}
|
||||
auto result = client->async_send_request(request);
|
||||
if (rclcpp::spin_until_future_complete(this->get_node_base_interface(), result) == rclcpp::FutureReturnCode::SUCCESS) {
|
||||
if (!result.get()->status) {
|
||||
RCLCPP_ERROR(this->get_logger(), "Failed to add serial listener");
|
||||
if (auto res = result.get()) {
|
||||
if (res->status) {
|
||||
|
||||
RCLCPP_INFO(this->get_logger(), "Publisher: %s", res->publisher.c_str());
|
||||
RCLCPP_INFO(this->get_logger(), "Subscriber: %s", res->subscriber.c_str());
|
||||
|
||||
subscriber_ = this->create_subscription<std_msgs::msg::String>(
|
||||
res->publisher, 10, [this](std_msgs::msg::String::SharedPtr msg) {
|
||||
processData(msg->data);
|
||||
});
|
||||
|
||||
publisher_ = this->create_publisher<modelec_interface::msg::ArduinoData>(res->subscriber, 10);
|
||||
} else {
|
||||
RCLCPP_ERROR(this->get_logger(), "Failed to add serial listener");
|
||||
}
|
||||
} else {
|
||||
RCLCPP_INFO(this->get_logger(), "Added serial listener");
|
||||
RCLCPP_ERROR(this->get_logger(), "Failed to ask for a serial listener");
|
||||
}
|
||||
} else {
|
||||
RCLCPP_ERROR(this->get_logger(), "Service call failed");
|
||||
}
|
||||
|
||||
subscriber_ = this->create_subscription<std_msgs::msg::String>(
|
||||
result.get()->publisher, 10, [this](std_msgs::msg::String::SharedPtr msg) {
|
||||
processData(msg->data);
|
||||
});
|
||||
publisher_ = this->create_publisher<modelec_interface::msg::ArduinoData>("arduino_processed_data", 10);
|
||||
}
|
||||
|
||||
void LogicProcessor::processData(const std::string &data) {
|
||||
auto processed_data = "Processed: " + data;
|
||||
RCLCPP_INFO(this->get_logger(), "%s", processed_data.c_str());
|
||||
auto msg = modelec_interface::msg::ArduinoData();
|
||||
std::vector<std::string> d = split(data, ':');
|
||||
|
||||
|
||||
Reference in New Issue
Block a user