new serial listener

This commit is contained in:
acki
2025-12-11 16:01:52 +01:00
parent b21ca2bffb
commit 675a72b506
6 changed files with 804 additions and 1 deletions

View File

@@ -35,6 +35,15 @@ target_include_directories(pcb_odo_interface PUBLIC
$<INSTALL_INTERFACE:include>
)
# PCB Odometry Node
add_executable(pcb_odo_interface_new src/pcb_odo_interface.new.cpp src/serial_listener.cpp)
ament_target_dependencies(pcb_odo_interface_new rclcpp std_msgs modelec_interfaces ament_index_cpp)
target_link_libraries(pcb_odo_interface_new modelec_utils::utils modelec_utils::config)
target_include_directories(pcb_odo_interface_new PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)
# PCB Alim Node
add_executable(pcb_alim_interface src/pcb_alim_interface.cpp)
ament_target_dependencies(pcb_alim_interface rclcpp std_msgs modelec_interfaces ament_index_cpp)
@@ -67,6 +76,7 @@ install(TARGETS
serial_listener
pcb_alim_interface
pcb_odo_interface
pcb_odo_interface_new
pcb_action_interface
DESTINATION lib/${PROJECT_NAME}
)

View File

@@ -0,0 +1,116 @@
#pragma once
#include <modelec_com/serial_listener.hpp>
#include <rclcpp/rclcpp.hpp>
#include <queue>
#include <mutex>
#include <future>
#include <std_msgs/msg/string.hpp>
#include <modelec_interfaces/msg/odometry_pos.hpp>
#include <modelec_interfaces/msg/odometry_speed.hpp>
#include <modelec_interfaces/msg/odometry_to_f.hpp>
#include <modelec_interfaces/msg/odometry_waypoint.hpp>
#include <modelec_interfaces/msg/odometry_waypoints.hpp>
#include <modelec_interfaces/msg/odometry_start.hpp>
#include <modelec_interfaces/msg/odometry_pid.hpp>
#include <modelec_interfaces/srv/odometry_position.hpp>
#include <modelec_interfaces/srv/odometry_speed.hpp>
#include <modelec_interfaces/srv/odometry_to_f.hpp>
#include <modelec_interfaces/srv/add_serial_listener.hpp>
#include <modelec_interfaces/srv/odometry_start.hpp>
#include <modelec_interfaces/srv/odometry_get_pid.hpp>
#include <modelec_interfaces/srv/odometry_set_pid.hpp>
#include <modelec_interfaces/srv/odometry_add_waypoint.hpp>
#include <std_msgs/msg/bool.hpp>
#include <std_msgs/msg/empty.hpp>
namespace Modelec
{
class PCBOdoInterface : public rclcpp::Node, public SerialListener
{
public:
PCBOdoInterface();
rclcpp::CallbackGroup::SharedPtr pcb_callback_group_;
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> pcb_executor_;
std::thread pcb_executor_thread_;
~PCBOdoInterface() override;
struct OdometryData
{
long x;
long y;
double theta;
};
struct PIDData
{
float p;
float i;
float d;
};
private:
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pcb_publisher_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr pcb_subscriber_;
void read(const std::string& msg) override;
rclcpp::Publisher<modelec_interfaces::msg::OdometryPos>::SharedPtr odo_pos_publisher_;
rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr odo_get_pos_sub_;
rclcpp::Publisher<modelec_interfaces::msg::OdometrySpeed>::SharedPtr odo_speed_publisher_;
rclcpp::Publisher<modelec_interfaces::msg::OdometryToF>::SharedPtr odo_tof_publisher_;
rclcpp::Publisher<modelec_interfaces::msg::OdometryWaypoint>::SharedPtr odo_waypoint_reach_publisher_;
rclcpp::Publisher<modelec_interfaces::msg::OdometryPid>::SharedPtr odo_pid_publisher_;
rclcpp::Subscription<modelec_interfaces::msg::OdometryWaypoint>::SharedPtr odo_add_waypoint_subscriber_;
rclcpp::Subscription<modelec_interfaces::msg::OdometryWaypoints>::SharedPtr odo_add_waypoints_subscriber_;
rclcpp::Subscription<modelec_interfaces::msg::OdometryPos>::SharedPtr odo_set_pos_subscriber_;
rclcpp::Subscription<modelec_interfaces::msg::OdometryPid>::SharedPtr odo_set_pid_subscriber_;
void AddWaypointCallback(const modelec_interfaces::msg::OdometryWaypoint::SharedPtr msg);
void AddWaypointsCallback(const modelec_interfaces::msg::OdometryWaypoints::SharedPtr msg);
void SetPosCallback(const modelec_interfaces::msg::OdometryPos::SharedPtr msg);
void SetPIDCallback(const modelec_interfaces::msg::OdometryPid::SharedPtr msg);
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr start_odo_sub_;
bool start_odo_ = false;
int timeout_ms = 1000;
int attempt = 5;
bool isOk = false;
public:
void SendToPCB(const std::string& data);
void SendToPCB(const std::string& order, const std::string& elem,
const std::vector<std::string>& data = {});
void GetData(const std::string& elem, const std::vector<std::string>& data = {});
void SendOrder(const std::string& elem, const std::vector<std::string>& data = {});
void GetPos();
void GetSpeed();
void GetToF(const int& tof);
void SetRobotPos(const modelec_interfaces::msg::OdometryPos::SharedPtr msg);
void SetRobotPos(long x, long y, double theta);
void AddWaypoints(modelec_interfaces::msg::OdometryWaypoints::SharedPtr msg);
void AddWaypoint(modelec_interfaces::msg::OdometryWaypoint::SharedPtr msg);
void AddWaypoint(int index, bool IsStopPoint, long x, long y, double theta);
void SetStart(const modelec_interfaces::msg::OdometryStart::SharedPtr msg);
void SetStart(bool start);
void GetPID();
void SetPID(const modelec_interfaces::msg::OdometryPid::SharedPtr msg);
void SetPID(std::string name, float p, float i, float d, std::optional<float> min = std::nullopt, std::optional<float> max = std::nullopt);
};
} // namespace Modelec

View File

@@ -0,0 +1,59 @@
#pragma once
#include <rclcpp/rclcpp.hpp>
#include <boost/asio.hpp>
#include <std_msgs/msg/string.hpp>
#include <modelec_interfaces/srv/add_serial_listener.hpp>
#include <deque>
#include <thread>
#include <mutex>
#define MAX_MESSAGE_LEN 1048
namespace Modelec
{
class SerialListener
{
protected:
bool status_;
int bauds_;
std::string serial_port_;
int max_message_len_;
boost::asio::io_service io_;
std::vector<char> read_buffer_;
std::deque<std::string> write_queue_;
std::mutex write_mutex_;
std::thread io_thread_;
void start_async_read();
void start_async_write();
public:
std::string name_;
boost::asio::serial_port port_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscriber_;
SerialListener();
SerialListener(const std::string& name, int bauds, const std::string& serial_port,
int max_message_len);
virtual ~SerialListener();
void close();
void open(const std::string& name, int bauds, const std::string& serial_port,
int max_message_len);
void SetMaxMessageLen(int max_message_len) { max_message_len_ = max_message_len; }
bool IsOk() const { return status_; }
void SetOk() { status_ = true; }
virtual void write(const std::string& msg);
virtual void read(const std::string& msg);
};
} // namespace Modelec

View File

@@ -0,0 +1,469 @@
#include <modelec_com/pcb_odo_interface.new.hpp>
#include <modelec_com/serial_listener.hpp>
#include <modelec_utils/utils.hpp>
#include <modelec_interfaces/srv/add_serial_listener.hpp>
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <modelec_utils/config.hpp>
namespace Modelec
{
PCBOdoInterface::PCBOdoInterface() : Node("pcb_odo_interface"), SerialListener()
{
declare_parameter<std::string>("serial_port", "/tmp/USB_ODO");
declare_parameter<int>("baudrate", 115200);
declare_parameter<std::string>("name", "pcb_odo");
// Service to create a new serial listener
auto request = std::make_shared<modelec_interfaces::srv::AddSerialListener::Request>();
request->name = get_parameter("name").as_string();
request->bauds = get_parameter("baudrate").as_int();
request->serial_port = get_parameter("serial_port").as_string();
this->open(request->name, request->bauds, request->serial_port, MAX_MESSAGE_LEN);
/*auto client = this->create_client<modelec_interfaces::srv::AddSerialListener>("add_serial_listener");
while (!client->wait_for_service(std::chrono::seconds(1)))
{
if (!rclcpp::ok())
{
RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting.");
return;
}
RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
}
auto result = client->async_send_request(request);
if (rclcpp::spin_until_future_complete(this->get_node_base_interface(), result) ==
rclcpp::FutureReturnCode::SUCCESS)
{
if (auto res = result.get())
{
if (res->success)
{
pcb_callback_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
rclcpp::SubscriptionOptions options;
options.callback_group = pcb_callback_group_;
pcb_subscriber_ = this->create_subscription<std_msgs::msg::String>(
res->publisher, 10,
[this](const std_msgs::msg::String::SharedPtr msg)
{
PCBCallback(msg);
},
options);
pcb_executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
pcb_executor_->add_callback_group(pcb_callback_group_, this->get_node_base_interface());
pcb_executor_thread_ = std::thread([this]()
{
pcb_executor_->spin();
});
pcb_publisher_ = this->create_publisher<std_msgs::msg::String>(res->subscriber, 10);
isOk = true;
SetStart(true);
SetPID("THETA", 14, 0, 0);
SetPID("POS", 10, 0, 0);
SetPID("LEFT", 5, 0, 0);
SetPID("RIGHT", 5, 0, 0);
}
else
{
RCLCPP_ERROR(this->get_logger(), "Failed to add serial listener");
}
}
else
{
RCLCPP_ERROR(this->get_logger(), "Failed to ask for a serial listener");
}
}
else
{
RCLCPP_ERROR(this->get_logger(), "Service call failed");
}*/
odo_pos_publisher_ = this->create_publisher<modelec_interfaces::msg::OdometryPos>(
"odometry/position", 10);
odo_get_pos_sub_ = this->create_subscription<std_msgs::msg::Empty>(
"odometry/get/pos", 30, [this](const std_msgs::msg::Empty::SharedPtr)
{
if (isOk)
{
GetPos();
}
});
odo_speed_publisher_ = this->create_publisher<modelec_interfaces::msg::OdometrySpeed>(
"odometry/speed", 10);
odo_tof_publisher_ = this->create_publisher<modelec_interfaces::msg::OdometryToF>(
"odometry/tof", 10);
odo_waypoint_reach_publisher_ = this->create_publisher<modelec_interfaces::msg::OdometryWaypoint>(
"odometry/waypoint_reach", 10);
odo_pid_publisher_ = this->create_publisher<modelec_interfaces::msg::OdometryPid>(
"odometry/get_pid", 10);
odo_add_waypoint_subscriber_ = this->create_subscription<modelec_interfaces::msg::OdometryWaypoint>(
"odometry/add_waypoint", 30,
[this](const modelec_interfaces::msg::OdometryWaypoint::SharedPtr msg)
{
AddWaypointCallback(msg);
});
odo_add_waypoints_subscriber_ = this->create_subscription<modelec_interfaces::msg::OdometryWaypoints>(
"odometry/add_waypoints", 30,
[this](const modelec_interfaces::msg::OdometryWaypoints::SharedPtr msg)
{
AddWaypointsCallback(msg);
});
odo_set_pos_subscriber_ = this->create_subscription<modelec_interfaces::msg::OdometryPos>(
"odometry/set_position", 10,
[this](const modelec_interfaces::msg::OdometryPos::SharedPtr msg)
{
SetPosCallback(msg);
});
odo_set_pid_subscriber_ = this->create_subscription<modelec_interfaces::msg::OdometryPid>(
"odometry/set_pid", 10,
[this](const modelec_interfaces::msg::OdometryPid::SharedPtr msg)
{
SetPIDCallback(msg);
});
start_odo_sub_ = this->create_subscription<std_msgs::msg::Bool>(
"odometry/start", 10,
[this](const std_msgs::msg::Bool::SharedPtr msg)
{
if (msg->data != start_odo_)
{
start_odo_ = msg->data;
SendOrder("START", {std::to_string(msg->data)});
}
});
}
PCBOdoInterface::~PCBOdoInterface()
{
SetStart(false);
if (pcb_executor_)
{
pcb_executor_->cancel();
}
if (pcb_executor_thread_.joinable())
{
pcb_executor_thread_.join();
}
}
void PCBOdoInterface::read(const std::string& msg)
{
RCLCPP_INFO(this->get_logger(), "Received from PCB: %s", msg.c_str());
std::vector<std::string> tokens = split(trim(msg), ';');
if (tokens.size() < 2)
{
RCLCPP_ERROR(this->get_logger(), "Invalid message format: %s", msg.c_str());
return;
}
if (tokens[0] == "SET")
{
if (tokens[1] == "POS")
{
long x = std::stol(tokens[2]);
long y = std::stol(tokens[3]);
double theta = std::stod(tokens[4]);
auto message = modelec_interfaces::msg::OdometryPos();
message.x = x;
message.y = y;
message.theta = theta;
if (odo_pos_publisher_) {
odo_pos_publisher_->publish(message);
}
}
else if (tokens[1] == "SPEED")
{
long x = std::stol(tokens[2]);
long y = std::stol(tokens[3]);
double theta = std::stod(tokens[4]);
auto message = modelec_interfaces::msg::OdometrySpeed();
message.x = x;
message.y = y;
message.theta = theta;
odo_speed_publisher_->publish(message);
}
else if (tokens[1] == "DIST")
{
int n = std::stoi(tokens[2]);
long dist = std::stol(tokens[3]);
auto message = modelec_interfaces::msg::OdometryToF();
message.n = n;
message.distance = dist;
odo_tof_publisher_->publish(message);
}
else if (tokens[1] == "WAYPOINT")
{
int id = std::stoi(tokens[2]);
auto message = modelec_interfaces::msg::OdometryWaypoint();
message.id = id;
odo_waypoint_reach_publisher_->publish(message);
}
else if (tokens[1] == "PID")
{
std::string name = tokens[2];
float p = std::stof(tokens[3]);
float i = std::stof(tokens[4]);
float d = std::stof(tokens[5]);
auto message = modelec_interfaces::msg::OdometryPid();
message.name = name;
message.p = p;
message.i = i;
message.d = d;
odo_pid_publisher_->publish(message);
}
}
else if (tokens[0] == "OK")
{
if (tokens[1] == "START")
{
start_odo_ = tokens[2] == "1";
}
else if (tokens[1] == "WAYPOINT")
{
}
else if (tokens[1] == "PID")
{
}
else if (tokens[1] == "POS")
{
}
else
{
RCLCPP_INFO(this->get_logger(), "PCB response: %s", msg.c_str());
}
}
else if (tokens[0] == "KO")
{
if (tokens[1] == "START")
{
}
else if (tokens[1] == "WAYPOINT")
{
}
else if (tokens[1] == "PID")
{
}
else
{
RCLCPP_WARN(this->get_logger(), "PCB error: %s", msg.c_str());
}
}
}
void PCBOdoInterface::AddWaypointsCallback(const modelec_interfaces::msg::OdometryWaypoints::SharedPtr msg) {
AddWaypoints(msg);
}
void PCBOdoInterface::AddWaypointCallback(const modelec_interfaces::msg::OdometryWaypoint::SharedPtr msg)
{
AddWaypoint(msg);
}
void PCBOdoInterface::SetPosCallback(const modelec_interfaces::msg::OdometryPos::SharedPtr msg)
{
SetRobotPos(msg);
}
void PCBOdoInterface::SetPIDCallback(const modelec_interfaces::msg::OdometryPid::SharedPtr msg)
{
SetPID(msg);
}
void PCBOdoInterface::SendToPCB(const std::string& data)
{
if (pcb_publisher_)
{
RCLCPP_DEBUG(this->get_logger(), "Sending to PCB: %s", data.c_str());
auto message = std_msgs::msg::String();
message.data = data;
pcb_publisher_->publish(message);
}
}
void PCBOdoInterface::SendToPCB(const std::string& order, const std::string& elem,
const std::vector<std::string>& data)
{
std::string command = order + ";" + elem;
for (const auto& d : data)
{
command += ";" + d;
}
command += "\n";
SendToPCB(command);
}
void PCBOdoInterface::GetData(const std::string& elem, const std::vector<std::string>& data)
{
SendToPCB("GET", elem, data);
}
void PCBOdoInterface::SendOrder(const std::string& elem, const std::vector<std::string>& data)
{
SendToPCB("SET", elem, data);
}
void PCBOdoInterface::GetPos()
{
GetData("POS");
}
void PCBOdoInterface::GetSpeed()
{
GetData("SPEED");
}
void PCBOdoInterface::GetToF(const int& tof)
{
GetData("DIST", {std::to_string(tof)});
}
void PCBOdoInterface::SetRobotPos(const modelec_interfaces::msg::OdometryPos::SharedPtr msg)
{
SetRobotPos(msg->x, msg->y, msg->theta);
}
void PCBOdoInterface::SetRobotPos(const long x, const long y, const double theta)
{
std::vector<std::string> data = {
std::to_string(x),
std::to_string(y),
std::to_string(theta)
};
SendOrder("POS", data);
}
void PCBOdoInterface::AddWaypoints(modelec_interfaces::msg::OdometryWaypoints::SharedPtr msg)
{
if (!start_odo_)
{
SendOrder("START", {std::to_string(true)});
}
std::vector<std::string> data;
for (const auto& wp : msg->waypoints)
{
data.push_back(std::to_string(wp.id));
data.push_back(std::to_string(wp.is_end));
data.push_back(std::to_string(wp.x));
data.push_back(std::to_string(wp.y));
data.push_back(std::to_string(wp.theta));
}
SendOrder("WAYPOINT", data);
}
void PCBOdoInterface::AddWaypoint(
const modelec_interfaces::msg::OdometryWaypoint::SharedPtr msg)
{
AddWaypoint(msg->id, msg->is_end, msg->x, msg->y, msg->theta);
}
void PCBOdoInterface::AddWaypoint(const int index, const bool IsStopPoint, const long x, const long y,
const double theta)
{
if (!start_odo_)
{
SendOrder("START", {std::to_string(true)});
}
std::vector<std::string> data = {
std::to_string(index),
std::to_string(IsStopPoint),
std::to_string(x),
std::to_string(y),
std::to_string(theta)
};
SendOrder("WAYPOINT", data);
}
void PCBOdoInterface::SetStart(const modelec_interfaces::msg::OdometryStart::SharedPtr msg)
{
SetStart(msg->start);
}
void PCBOdoInterface::SetStart(bool start)
{
SendOrder("START", {std::to_string(start)});
}
void PCBOdoInterface::GetPID()
{
GetData("PID");
}
void PCBOdoInterface::SetPID(const modelec_interfaces::msg::OdometryPid::SharedPtr msg)
{
SetPID(msg->name, msg->p, msg->i, msg->d);
}
void PCBOdoInterface::SetPID(std::string name, float p, float i, float d, std::optional<float> min, std::optional<float> max)
{
std::vector<std::string> data = {
name,
std::to_string(p),
std::to_string(i),
std::to_string(d)
};
if (min.has_value())
{
data.push_back(std::to_string(min.value()));
}
if (max.has_value())
{
data.push_back(std::to_string(max.value()));
}
SendOrder("PID", data);
}
} // Modelec
#ifndef MODELEC_COM_TESTING
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<Modelec::PCBOdoInterface>();
rclcpp::executors::MultiThreadedExecutor executor(
rclcpp::ExecutorOptions(), 2);
executor.add_node(node);
executor.spin();
rclcpp::shutdown();
return 0;
}
#endif

View File

@@ -0,0 +1,149 @@
#include <modelec_com/serial_listener.hpp>
#include <modelec_utils/utils.hpp>
namespace Modelec
{
SerialListener::SerialListener() : io_(), port_(io_)
{
}
SerialListener::SerialListener(const std::string& name, int bauds, const std::string& serial_port,
int max_message_len) : io_(), port_(io_)
{
open(name, bauds, serial_port, max_message_len);
}
SerialListener::~SerialListener()
{
if (status_)
{
close();
}
}
void SerialListener::close()
{
if (status_)
{
if (port_.is_open()) port_.close();
io_.stop();
if (io_thread_.joinable()) io_thread_.join();
status_ = false;
}
}
void SerialListener::open(const std::string& name, int bauds, const std::string& serial_port,
int max_message_len) {
this->name_ = name;
this->bauds_ = bauds;
this->serial_port_ = serial_port;
this->max_message_len_ = max_message_len;
try
{
port_.open(serial_port_);
port_.set_option(boost::asio::serial_port_base::baud_rate(bauds_));
status_ = true;
}
catch (boost::system::system_error& e)
{
RCLCPP_ERROR(rclcpp::get_logger("SerialListener"), "Failed to open serial port: %s", e.what());
status_ = false;
return;
}
read_buffer_.resize(max_message_len_);
start_async_read();
io_thread_ = std::thread([this]()
{
try
{
io_.run();
}
catch (const std::exception& e)
{
RCLCPP_ERROR(rclcpp::get_logger("SerialListener"), "IO thread exception: %s", e.what());
}
});
}
void SerialListener::start_async_read()
{
if (!status_) start_async_read();
port_.async_read_some(
boost::asio::buffer(read_buffer_),
[this](const boost::system::error_code& ec, std::size_t bytes_transferred)
{
if (!ec && bytes_transferred > 0)
{
std::string d = std::string(read_buffer_.begin(), read_buffer_.begin() + bytes_transferred);
auto allMess = Modelec::split(d, '\n');
for (const auto& mess : allMess)
{
if (!mess.empty())
{
// RCLCPP_INFO(rclcpp::get_logger("SerialListener"), "Received message: %s", mess.c_str());
/*auto msg = std_msgs::msg::String();
msg.data = mess;
if (publisher_)
{
publisher_->publish(msg);
}*/
read(mess);
}
}
start_async_read(); // continue reading
}
else
{
RCLCPP_ERROR(rclcpp::get_logger("SerialListener"), "Async read error: %s", ec.message().c_str());
}
});
}
void SerialListener::write(const std::string& msg)
{
std::lock_guard<std::mutex> lock(write_mutex_);
bool write_in_progress = !write_queue_.empty();
write_queue_.push_back(msg);
if (!write_in_progress)
{
start_async_write();
}
}
void SerialListener::start_async_write()
{
if (write_queue_.empty()) return;
boost::asio::async_write(
port_,
boost::asio::buffer(write_queue_.front()),
[this](const boost::system::error_code& ec, std::size_t /*length*/)
{
std::lock_guard<std::mutex> lock(write_mutex_);
if (!ec)
{
write_queue_.pop_front();
if (!write_queue_.empty())
{
start_async_write(); // continue writing
}
}
else
{
RCLCPP_ERROR(rclcpp::get_logger("SerialListener"), "Async write error: %s", ec.message().c_str());
}
});
}
void SerialListener::read(const std::string&) {
// Default implementation does nothing
}
} // namespace Modelec

View File

@@ -96,7 +96,7 @@ def generate_launch_description():
Node(package='modelec_com', executable='serial_listener', name='serial_listener'),
Node(
package='modelec_com',
executable='pcb_odo_interface',
executable='pcb_odo_interface_new',
name='pcb_odo_interface',
parameters=[{
'serial_port': "/dev/USB_ODO",