Merge pull request #1 from tlab-wide/feature/add-program-options

Add ROS2 Parameter to specify network interface
This commit is contained in:
Yu Asabe 2021-12-08 20:34:19 +09:00 committed by GitHub
commit ef581cd510
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
3 changed files with 10 additions and 3 deletions

View File

@ -1,3 +1,5 @@
<launch> <launch>
<node pkg="autoware_v2x" exec="autoware_v2x_node" namespace="v2x" output="screen" emulate_tty="true" /> <node pkg="autoware_v2x" exec="autoware_v2x_node" namespace="v2x" output="screen" emulate_tty="true">
<param name="network_interface" value="vmnet1"/>
</node>
</launch> </launch>

View File

@ -106,8 +106,11 @@ namespace v2x
boost::asio::io_service io_service; boost::asio::io_service io_service;
TimeTrigger trigger(io_service); TimeTrigger trigger(io_service);
const char* device_name = "vmnet1"; std::string network_interface;
EthernetDevice device(device_name); node_->get_parameter("network_interface", network_interface);
RCLCPP_INFO(node_->get_logger(), "Network Interface: %s", network_interface.c_str());
EthernetDevice device(network_interface.c_str());
vanetza::MacAddress mac_address = device.address(); vanetza::MacAddress mac_address = device.address();
std::stringstream sout; std::stringstream sout;

View File

@ -34,6 +34,8 @@ namespace v2x
publisher_ = create_publisher<autoware_perception_msgs::msg::DynamicObjectArray>("/perception/object_recognition/objects", rclcpp::QoS{10}); publisher_ = create_publisher<autoware_perception_msgs::msg::DynamicObjectArray>("/perception/object_recognition/objects", rclcpp::QoS{10});
this->declare_parameter<std::string>("network_interface", "vmnet1");
app = new V2XApp(this); app = new V2XApp(this);
boost::thread v2xApp(boost::bind(&V2XApp::start, app)); boost::thread v2xApp(boost::bind(&V2XApp::start, app));