Skip to content

Commit

Permalink
Remove viewpoint object
Browse files Browse the repository at this point in the history
F
  • Loading branch information
Jaeyoung-Lim committed Nov 28, 2023
1 parent 535cdd6 commit 2e780e4
Show file tree
Hide file tree
Showing 5 changed files with 0 additions and 354 deletions.
183 changes: 0 additions & 183 deletions terrain_navigation/include/terrain_navigation/viewpoint.h

This file was deleted.

97 changes: 0 additions & 97 deletions terrain_navigation/include/terrain_navigation/visualization.h

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,6 @@
#include <mutex>

#include <terrain_navigation/profiler.h>
#include <terrain_navigation/viewpoint.h>

#include "terrain_navigation_ros/visualization.h"
#include "terrain_planner/common.h"
Expand Down Expand Up @@ -173,8 +172,6 @@ class TerrainPlanner {
ros::Publisher rallypoint_pub_;
ros::Publisher candidate_goal_pub_;
ros::Publisher candidate_start_pub_;
ros::Publisher viewpoint_pub_;
ros::Publisher planned_viewpoint_pub_;
ros::Publisher tree_pub_;
ros::Publisher vehicle_velocity_pub_;
ros::Publisher path_segment_pub_;
Expand All @@ -184,7 +181,6 @@ class TerrainPlanner {
ros::Subscriber mavstate_sub_;
ros::Subscriber mavmission_sub_;
ros::Subscriber global_origin_sub_;
ros::Subscriber image_captured_sub_;

ros::ServiceServer setlocation_serviceserver_;
ros::ServiceServer setmaxaltitude_serviceserver_;
Expand Down Expand Up @@ -234,11 +230,8 @@ class TerrainPlanner {
std::mutex goal_mutex_; // protects g_i

std::vector<Eigen::Vector3d> vehicle_position_history_;
std::vector<ViewPoint> added_viewpoint_list;
std::vector<ViewPoint> planned_viewpoint_list;
std::vector<geometry_msgs::PoseStamped> posehistory_vector_;
std::vector<geometry_msgs::PoseStamped> referencehistory_vector_;
std::vector<ViewPoint> viewpoints_;
Eigen::Vector3d vehicle_position_{Eigen::Vector3d::Zero()};
Eigen::Vector3d vehicle_velocity_{Eigen::Vector3d::Zero()};
Eigen::Vector4d vehicle_attitude_{Eigen::Vector4d(1.0, 0.0, 0.0, 0.0)};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,27 +126,6 @@ inline void publishCameraView(const ros::Publisher pub, const Eigen::Vector3d& p
pub.publish(marker);
}

inline void publishViewpoints(const ros::Publisher pub, std::vector<ViewPoint>& viewpoint_vector,
Eigen::Vector3d color = Eigen::Vector3d(0.0, 0.0, 1.0)) {
visualization_msgs::MarkerArray msg;

std::vector<visualization_msgs::Marker> marker;
visualization_msgs::Marker mark;
mark.action = visualization_msgs::Marker::DELETEALL;
marker.push_back(mark);
msg.markers = marker;
pub.publish(msg);

std::vector<visualization_msgs::Marker> viewpoint_marker_vector;
int i = 0;
for (auto viewpoint : viewpoint_vector) {
viewpoint_marker_vector.insert(viewpoint_marker_vector.begin(), Viewpoint2MarkerMsg(i, viewpoint, color));
i++;
}
msg.markers = viewpoint_marker_vector;
pub.publish(msg);
}

void publishCandidateManeuvers(const ros::Publisher& pub, const std::vector<Path>& candidate_maneuvers,
bool visualize_invalid_trajectories = false) {
visualization_msgs::MarkerArray msg;
Expand Down
Loading

0 comments on commit 2e780e4

Please sign in to comment.