mirror of
https://github.com/modelec/modelec-marcel-ROS.git
synced 2026-01-18 16:47:43 +01:00
new serial listener
This commit is contained in:
@@ -133,7 +133,7 @@ if __name__ == '__main__':
|
|||||||
sim.stop()
|
sim.stop()
|
||||||
print("Simulation stopped")
|
print("Simulation stopped")
|
||||||
|
|
||||||
# socat -d -d pty,raw,echo=0,link=/tmp/MARCEL_ACTION_SIM pty,raw,echo=0,link=/tmp/MARCEL_ACTION
|
# socat -d -d pty,raw,echo=0,link=/tmp/ACTION_SIM pty,raw,echo=0,link=/tmp/ACTION_USB
|
||||||
# python3 simulated_pcb/action.py --port /tmp/MARCEL_ACTION_SIM
|
# python3 simulated_pcb/action.py --port /tmp/ACTION_SIM
|
||||||
# socat -d -d pty,raw,echo=0,link=/tmp/ENEMY_ACTION_SIM pty,raw,echo=0,link=/tmp/ENEMY_ACTION
|
# socat -d -d pty,raw,echo=0,link=/tmp/ODO_SIM pty,raw,echo=0,link=/tmp/ODO_USB
|
||||||
# python3 simulated_pcb/action.py --port /tmp/ENEMY_ACTION_SIM
|
# python3 simulated_pcb/action.py --port /tmp/ODO_SIM
|
||||||
|
|||||||
@@ -37,9 +37,6 @@ namespace Modelec
|
|||||||
public:
|
public:
|
||||||
PCBOdoInterface();
|
PCBOdoInterface();
|
||||||
|
|
||||||
rclcpp::CallbackGroup::SharedPtr pcb_callback_group_;
|
|
||||||
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> pcb_executor_;
|
|
||||||
std::thread pcb_executor_thread_;
|
|
||||||
~PCBOdoInterface() override;
|
~PCBOdoInterface() override;
|
||||||
|
|
||||||
struct OdometryData
|
struct OdometryData
|
||||||
@@ -57,9 +54,6 @@ namespace Modelec
|
|||||||
};
|
};
|
||||||
|
|
||||||
private:
|
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;
|
void read(const std::string& msg) override;
|
||||||
|
|
||||||
rclcpp::Publisher<modelec_interfaces::msg::OdometryPos>::SharedPtr odo_pos_publisher_;
|
rclcpp::Publisher<modelec_interfaces::msg::OdometryPos>::SharedPtr odo_pos_publisher_;
|
||||||
|
|||||||
@@ -153,20 +153,11 @@ namespace Modelec
|
|||||||
PCBOdoInterface::~PCBOdoInterface()
|
PCBOdoInterface::~PCBOdoInterface()
|
||||||
{
|
{
|
||||||
SetStart(false);
|
SetStart(false);
|
||||||
|
|
||||||
if (pcb_executor_)
|
|
||||||
{
|
|
||||||
pcb_executor_->cancel();
|
|
||||||
}
|
|
||||||
if (pcb_executor_thread_.joinable())
|
|
||||||
{
|
|
||||||
pcb_executor_thread_.join();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void PCBOdoInterface::read(const std::string& msg)
|
void PCBOdoInterface::read(const std::string& msg)
|
||||||
{
|
{
|
||||||
RCLCPP_INFO(this->get_logger(), "Received from PCB: %s", msg.c_str());
|
RCLCPP_DEBUG(this->get_logger(), "Received from PCB: %s", msg.c_str());
|
||||||
std::vector<std::string> tokens = split(trim(msg), ';');
|
std::vector<std::string> tokens = split(trim(msg), ';');
|
||||||
if (tokens.size() < 2)
|
if (tokens.size() < 2)
|
||||||
{
|
{
|
||||||
@@ -300,12 +291,10 @@ namespace Modelec
|
|||||||
|
|
||||||
void PCBOdoInterface::SendToPCB(const std::string& data)
|
void PCBOdoInterface::SendToPCB(const std::string& data)
|
||||||
{
|
{
|
||||||
if (pcb_publisher_)
|
if (IsOk())
|
||||||
{
|
{
|
||||||
RCLCPP_DEBUG(this->get_logger(), "Sending to PCB: %s", data.c_str());
|
RCLCPP_DEBUG(this->get_logger(), "Sending to PCB: %s", data.c_str());
|
||||||
auto message = std_msgs::msg::String();
|
this->write(data);
|
||||||
message.data = data;
|
|
||||||
pcb_publisher_->publish(message);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -109,7 +109,7 @@ def generate_launch_description():
|
|||||||
executable='pcb_action_interface',
|
executable='pcb_action_interface',
|
||||||
name='pcb_action_interface',
|
name='pcb_action_interface',
|
||||||
parameters=[{
|
parameters=[{
|
||||||
'serial_port': "/tmp/USB_ACTION",
|
'serial_port': "/dev/USB_ACTION",
|
||||||
'baudrate': 115200,
|
'baudrate': 115200,
|
||||||
'name': "pcb_action",
|
'name': "pcb_action",
|
||||||
}]
|
}]
|
||||||
|
|||||||
Reference in New Issue
Block a user