Skip to content
Snippets Groups Projects
Commit 168f3484 authored by Martina Rivizzigno's avatar Martina Rivizzigno Committed by Julian Kent
Browse files

world visualizer: add to the constructor the node/nodelet namespace where (#512)

the world file name parameter lives
parent f1c5064f
No related branches found
No related tags found
No related merge requests found
......@@ -49,11 +49,12 @@ class WorldVisualizer {
ros::Publisher drone_pub_;
std::string world_path_;
std::string nodelet_ns_;
void loopCallback(const ros::TimerEvent& event);
public:
WorldVisualizer(const ros::NodeHandle& nh);
WorldVisualizer(const ros::NodeHandle& nh, const std::string& nodelet_ns);
/**
* @brief initializes all publishers used for local planner visualization
......
......@@ -4,7 +4,8 @@
namespace avoidance {
WorldVisualizer::WorldVisualizer(const ros::NodeHandle& nh) : nh_(nh) {
WorldVisualizer::WorldVisualizer(const ros::NodeHandle& nh, const std::string& nodelet_ns)
: nh_(nh), nodelet_ns_(nodelet_ns) {
pose_sub_ = nh_.subscribe<const geometry_msgs::PoseStamped&>("/mavros/local_position/pose", 1,
&WorldVisualizer::positionCallback, this);
......@@ -12,7 +13,13 @@ WorldVisualizer::WorldVisualizer(const ros::NodeHandle& nh) : nh_(nh) {
drone_pub_ = nh_.advertise<visualization_msgs::Marker>("/drone", 1);
loop_timer_ = nh_.createTimer(ros::Duration(2.0), &WorldVisualizer::loopCallback, this);
nh_.param<std::string>("/local_planner_nodelet/world_name", world_path_, "");
std::string world_string;
if (!nodelet_ns_.empty()) {
world_string = nodelet_ns_ + "/world_name";
} else {
world_string = "/world_name";
}
nh_.param<std::string>(world_string, world_path_, "");
}
void WorldVisualizer::loopCallback(const ros::TimerEvent& event) {
......
......@@ -16,7 +16,7 @@ GlobalPlannerNode::GlobalPlannerNode(const ros::NodeHandle& nh, const ros::NodeH
server_.setCallback(f);
#ifndef DISABLE_SIMULATION
world_visualizer_.reset(new avoidance::WorldVisualizer(nh_));
world_visualizer_.reset(new avoidance::WorldVisualizer(nh_, ros::this_node::getName()));
#endif
avoidance_node_.init();
......@@ -408,4 +408,4 @@ void GlobalPlannerNode::publishSetpoint() {
bool GlobalPlannerNode::isCloseToGoal() { return distance(current_goal_, last_pos_) < 1.5; }
} // namespace global_planner
\ No newline at end of file
} // namespace global_planner
......@@ -58,7 +58,7 @@ void LocalPlannerNodelet::InitializeNodelet() {
avoidance_node_.reset(new AvoidanceNode(nh_, nh_private_));
#ifndef DISABLE_SIMULATION
world_visualizer_.reset(new WorldVisualizer(nh_));
world_visualizer_.reset(new WorldVisualizer(nh_, nodelet::Nodelet::getName()));
#endif
readParams();
......
......@@ -8,9 +8,8 @@ SafeLandingPlannerNode::SafeLandingPlannerNode(const ros::NodeHandle &nh) : nh_(
safe_landing_planner_.reset(new SafeLandingPlanner());
#ifndef DISABLE_SIMULATION
world_visualizer_.reset(new avoidance::WorldVisualizer(nh_));
world_visualizer_.reset(new avoidance::WorldVisualizer(nh_, ros::this_node::getName()));
#endif
visualizer_.initializePublishers(nh_);
std::string camera_topic;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment