add parameter and launch for lidar reader
This commit is contained in:
23
src/object_detection/launch/object_detection_launch_both.py
Normal file
23
src/object_detection/launch/object_detection_launch_both.py
Normal file
@@ -0,0 +1,23 @@
|
|||||||
|
from launch import LaunchDescription
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package="object_detection",
|
||||||
|
executable="multiflex_reader",
|
||||||
|
name="multiflex_reader",
|
||||||
|
parameters=[
|
||||||
|
{"multiflex_serial_port": "/dev/ttyACM0"}
|
||||||
|
]
|
||||||
|
),
|
||||||
|
Node(
|
||||||
|
package="object_detection",
|
||||||
|
executable="lidar_reader",
|
||||||
|
name="lidar_reader",
|
||||||
|
parameters=[
|
||||||
|
{"lidar_serial_port": "/dev/ttyUSB0"} # TODO test
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
])
|
||||||
@@ -8,7 +8,7 @@ def generate_launch_description():
|
|||||||
executable="multiflex_reader",
|
executable="multiflex_reader",
|
||||||
name="multiflex_reader",
|
name="multiflex_reader",
|
||||||
parameters=[
|
parameters=[
|
||||||
{"serial_port": "/dev/ttyACM0"}
|
{"multiflex_serial_port": "/dev/ttyACM0"}
|
||||||
]
|
]
|
||||||
)
|
)
|
||||||
|
|
||||||
@@ -51,13 +51,19 @@ public:
|
|||||||
LidarReader()
|
LidarReader()
|
||||||
: Node("lidar_reader")
|
: Node("lidar_reader")
|
||||||
{
|
{
|
||||||
|
|
||||||
|
rcl_interfaces::msg::ParameterDescriptor descriptor = rcl_interfaces::msg::ParameterDescriptor{};
|
||||||
|
descriptor.description = "serial port for the USB port of the LIDAR";
|
||||||
|
|
||||||
|
this->declare_parameter("lidar_serial_port", "/dev/ttyACM0", descriptor);
|
||||||
|
|
||||||
publisher_ = this->create_publisher<object_detection::msg::LidarReading>("drone/object_detection", 10);
|
publisher_ = this->create_publisher<object_detection::msg::LidarReading>("drone/object_detection", 10);
|
||||||
timer_ = this->create_wall_timer(500ms, std::bind(&LidarReader::read_lidar_data, this));
|
timer_ = this->create_wall_timer(500ms, std::bind(&LidarReader::read_lidar_data, this));
|
||||||
|
|
||||||
ITerarangerTowerEvo::ImuMode mode(ITerarangerTowerEvo::QuaternionLinearAcc);
|
ITerarangerTowerEvo::ImuMode mode(ITerarangerTowerEvo::QuaternionLinearAcc);
|
||||||
|
|
||||||
factory = terabee::ITerarangerFactory::getFactory();
|
factory = terabee::ITerarangerFactory::getFactory();
|
||||||
tower = factory->createTerarangerTowerEvo("/dev/ttyACM0");
|
tower = factory->createTerarangerTowerEvo(this->get_parameter("lidar_serial_port"));
|
||||||
|
|
||||||
if (!tower)
|
if (!tower)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -23,10 +23,10 @@ public:
|
|||||||
{
|
{
|
||||||
rcl_interfaces::msg::ParameterDescriptor serial_port_descriptor = rcl_interfaces::msg::ParameterDescriptor{};
|
rcl_interfaces::msg::ParameterDescriptor serial_port_descriptor = rcl_interfaces::msg::ParameterDescriptor{};
|
||||||
serial_port_descriptor.description = "Serial port of the USB port that the multiflex PCB is connected to.";
|
serial_port_descriptor.description = "Serial port of the USB port that the multiflex PCB is connected to.";
|
||||||
this->declare_parameter("serial_port", "/dev/ttyACM0", serial_port_descriptor);
|
this->declare_parameter("multiflex_serial_port", "/dev/ttyACM0", serial_port_descriptor);
|
||||||
|
|
||||||
factory = terabee::ITerarangerFactory::getFactory();
|
factory = terabee::ITerarangerFactory::getFactory();
|
||||||
multiflex = factory->createTerarangerMultiflex(this->get_parameter("serial_port").as_string());
|
multiflex = factory->createTerarangerMultiflex(this->get_parameter("multiflex_serial_port").as_string());
|
||||||
|
|
||||||
if (!multiflex)
|
if (!multiflex)
|
||||||
{
|
{
|
||||||
|
|||||||
Reference in New Issue
Block a user