Skip to content

Commit f3d6ac1

Browse files
committed
Changed nav_msgs:Path to lart_msgs PathSpline
1 parent 924629c commit f3d6ac1

File tree

2 files changed

+5
-7
lines changed

2 files changed

+5
-7
lines changed

safety_monitor/include/Safety_monitor/monitor.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111

1212
#include "timeFreq.h"
1313
#include "rclcpp/rclcpp.hpp"
14-
#include "nav_msgs/msg/path.hpp"
14+
#include "lart_msgs/msg/path_spline.hpp"
1515
#include "lart_msgs/msg/state.hpp"
1616
#include "sensor_msgs/msg/image.hpp"
1717
#include "lart_msgs/msg/cone_array.hpp"
@@ -46,7 +46,7 @@ class SafetyMonitor : public rclcpp::Node
4646

4747
//Subs for the mapper|planner|control
4848
rclcpp::Subscription<lart_msgs::msg::ConeArray>::SharedPtr mapping_sub;
49-
rclcpp::Subscription<nav_msgs::msg::Path>::SharedPtr planning_sub;
49+
rclcpp::Subscription<lart_msgs::msg::PathSpline>::SharedPtr planning_sub;
5050
rclcpp::Subscription<lart_msgs::msg::DynamicsCMD>::SharedPtr control_sub;
5151

5252
//Sub for the state
@@ -72,7 +72,7 @@ class SafetyMonitor : public rclcpp::Node
7272
void depthInfo_callback(const sensor_msgs::msg::CameraInfo::SharedPtr msg);
7373

7474
void mapping_callback(const lart_msgs::msg::ConeArray::SharedPtr msg);
75-
void planning_callback(const nav_msgs::msg::Path::SharedPtr msg);
75+
void planning_callback(const lart_msgs::msg::PathSpline::SharedPtr msg);
7676
void control_callback(const lart_msgs::msg::DynamicsCMD::SharedPtr msg);
7777

7878

safety_monitor/src/monitor.cpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ SafetyMonitor::SafetyMonitor() : Node("safety_monitor")
4141
depth_info_sub = this->create_subscription<sensor_msgs::msg::CameraInfo>(topics[5], 10, std::bind(&SafetyMonitor::depthInfo_callback,this, _1));
4242

4343
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));
4545
control_sub = this->create_subscription<lart_msgs::msg::DynamicsCMD>(topics[8], 10, std::bind(&SafetyMonitor::control_callback,this, _1));
4646

4747

@@ -56,8 +56,6 @@ SafetyMonitor::SafetyMonitor() : Node("safety_monitor")
5656

5757
}
5858

59-
60-
// TODO: Optimize later!!!
6159
void SafetyMonitor::leftImage_callback(const sensor_msgs::msg::Image::SharedPtr msg)
6260
{
6361
(void) msg;
@@ -107,7 +105,7 @@ void SafetyMonitor::mapping_callback(const lart_msgs::msg::ConeArray::SharedPtr
107105
update_time(topics[6]);
108106
}
109107

110-
void SafetyMonitor::planning_callback(const nav_msgs::msg::Path::SharedPtr msg)
108+
void SafetyMonitor::planning_callback(const lart_msgs::msg::PathSpline::SharedPtr msg)
111109
{
112110
(void) msg;
113111
RCLCPP_INFO(this->get_logger(), "Planner msg has been received");

0 commit comments

Comments
 (0)