@@ -41,7 +41,7 @@ SafetyMonitor::SafetyMonitor() : Node("safety_monitor")
41
41
depth_info_sub = this ->create_subscription <sensor_msgs::msg::CameraInfo>(topics[5 ], 10 , std::bind (&SafetyMonitor::depthInfo_callback,this , _1));
42
42
43
43
mapping_sub = this ->create_subscription <lart_msgs::msg::ConeArray>(topics[6 ], 10 , std::bind (&SafetyMonitor::mapping_callback,this , _1));
44
- planning_sub = this ->create_subscription <nav_msgs ::msg::Path >(topics[7 ], 10 , std::bind (&SafetyMonitor::planning_callback,this , _1));
44
+ planning_sub = this ->create_subscription <lart_msgs ::msg::PathSpline >(topics[7 ], 10 , std::bind (&SafetyMonitor::planning_callback,this , _1));
45
45
control_sub = this ->create_subscription <lart_msgs::msg::DynamicsCMD>(topics[8 ], 10 , std::bind (&SafetyMonitor::control_callback,this , _1));
46
46
47
47
@@ -56,8 +56,6 @@ SafetyMonitor::SafetyMonitor() : Node("safety_monitor")
56
56
57
57
}
58
58
59
-
60
- // TODO: Optimize later!!!
61
59
void SafetyMonitor::leftImage_callback (const sensor_msgs::msg::Image::SharedPtr msg)
62
60
{
63
61
(void ) msg;
@@ -107,7 +105,7 @@ void SafetyMonitor::mapping_callback(const lart_msgs::msg::ConeArray::SharedPtr
107
105
update_time (topics[6 ]);
108
106
}
109
107
110
- void SafetyMonitor::planning_callback (const nav_msgs ::msg::Path ::SharedPtr msg)
108
+ void SafetyMonitor::planning_callback (const lart_msgs ::msg::PathSpline ::SharedPtr msg)
111
109
{
112
110
(void ) msg;
113
111
RCLCPP_INFO (this ->get_logger (), " Planner msg has been received" );
0 commit comments