Skip to content

Commit

Permalink
Created new ros2 msg for targetlist
Browse files Browse the repository at this point in the history
Provide the targetlist values as topic for all interfaces and sensor types.
  • Loading branch information
smartSRA committed Nov 8, 2023
1 parent 192b17b commit a7c1c76
Show file tree
Hide file tree
Showing 4 changed files with 259 additions and 48 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include "umrr_ros2_msgs/srv/set_ip.hpp"
#include "umrr_ros2_msgs/srv/set_mode.hpp"
#include "umrr_ros2_msgs/srv/firmware_download.hpp"
#include "umrr_ros2_msgs/msg/target_list.hpp"

namespace smartmicro {
namespace drivers {
Expand Down Expand Up @@ -402,6 +403,9 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node {
std::array<rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr,
detail::kMaxSensorCount>
m_publishers{};
std::array<rclcpp::Publisher<umrr_ros2_msgs::msg::TargetList>::SharedPtr,
detail::kMaxSensorCount>
m_targetlist_publishers{};
std::size_t m_number_of_sensors{};
std::size_t m_number_of_adapters{};
rclcpp::TimerBase::SharedPtr timer;
Expand Down
Loading

0 comments on commit a7c1c76

Please sign in to comment.