Skip to content

Commit

Permalink
snowsampler_rviz code cleanup (#9)
Browse files Browse the repository at this point in the history
* removed pose widget (still working)

* compiling

* cleanup the imports

* clang-format
  • Loading branch information
Claudio-Chies authored Apr 22, 2024
1 parent 854d081 commit b2d4806
Show file tree
Hide file tree
Showing 7 changed files with 22 additions and 369 deletions.
4 changes: 0 additions & 4 deletions snowsampler_rviz/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,11 @@ add_definitions(-std=c++11)
set(CMAKE_AUTOMOC OFF)

set(HEADER_FILES_QT
include/snowsampler_rviz/pose_widget.h
include/snowsampler_rviz/planning_panel.h
include/snowsampler_rviz/edit_button.h
)

set(SRC_FILES
src/planning_panel.cpp
src/pose_widget.cpp
src/edit_button.cpp
src/goal_marker.cpp
)

Expand Down
49 changes: 0 additions & 49 deletions snowsampler_rviz/include/snowsampler_rviz/edit_button.h

This file was deleted.

49 changes: 18 additions & 31 deletions snowsampler_rviz/include/snowsampler_rviz/planning_panel.h
Original file line number Diff line number Diff line change
@@ -1,30 +1,31 @@
#ifndef snowsampler_rviz_PLANNING_PANEL_H_
#define snowsampler_rviz_PLANNING_PANEL_H_

#ifndef Q_MOC_RUN
#include <geometry_msgs/PoseStamped.h>
#include <grid_map_geo_msgs/GeographicMapInfo.h>
#include <mav_msgs/conversions.h>
#include <mav_msgs/eigen_mav_msgs.h>
#include <planner_msgs/NavigationStatus.h>
#include <planner_msgs/SetService.h>
#include <ros/ros.h>
#include <rviz/panel.h>
#include <snowsampler_msgs/SetAngle.h>
#include <snowsampler_msgs/SetMeasurementDepth.h>
#include <snowsampler_msgs/Trigger.h>
#include <snowsampler_rviz/goal_marker.h>
#include <std_msgs/Float64.h>
#include <std_msgs/Int8.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <QCheckBox>
#include <QGridLayout>
#include <QGroupBox>
#include <QLabel>
#include <QLineEdit>
#include <QPushButton>
#include <QTimer>

#include "geometry_msgs/PoseStamped.h"
#include "mav_msgs/conversions.h"
#include "mav_msgs/eigen_mav_msgs.h"
#include "snowsampler_msgs/SetMeasurementDepth.h"
#include "snowsampler_msgs/Trigger.h"
#include "snowsampler_rviz/edit_button.h"
#include "snowsampler_rviz/goal_marker.h"
#include "snowsampler_rviz/pose_widget.h"
#include "grid_map_geo_msgs/GeographicMapInfo.h"
#include "std_msgs/Float64.h"
#include "std_msgs/Int8.h"

#endif
#include <thread>

enum PLANNER_STATE { HOLD = 1, NAVIGATE = 2, ROLLOUT = 3, ABORT = 4, RETURN = 5 };
enum SSPState {
Expand Down Expand Up @@ -65,10 +66,6 @@ class PlanningPanel : public rviz::Panel {
virtual void save(rviz::Config config) const;
virtual void onInitialize();

// All the settings to manage pose <-> edit mapping.
void registerPoseWidget(PoseWidget* widget);
void registerEditButton(EditButton* button);

// Callback from ROS when the pose updates:
void legAngleCallback(const std_msgs::Float64& msg);
void targetAngleCallback(const std_msgs::Float64& msg);
Expand All @@ -77,11 +74,8 @@ class PlanningPanel : public rviz::Panel {
void mapInfoCallback(const grid_map_geo_msgs::GeographicMapInfo& msg);
// Next come a couple of public Qt slots.
public Q_SLOTS:
void startEditing(const std::string& id);
void finishEditing(const std::string& id);
void widgetPoseUpdated(const std::string& id, mav_msgs::EigenTrajectoryPoint& pose);

void callSetAngleService(double angle);
void terrainAlignmentStateChanged(int state);
void setPlannerModeServiceTakeoff();
void setPlannerModeServiceLand();
void setPlannerModeServiceGoTo();
Expand Down Expand Up @@ -124,25 +118,18 @@ class PlanningPanel : public rviz::Panel {
QPushButton* ssp_stop_measurement_button_;
QPushButton* ssp_go_home_button_;
QPushButton* ssp_set_measurement_depth_button_;
PoseWidget* start_pose_widget_;
PoseWidget* goal_pose_widget_;
QPushButton* set_goal_button_;
QPushButton* set_start_button_;
std::vector<QPushButton*> set_planner_state_buttons_;
QPushButton* controller_button_;

// Keep track of all the pose <-> button widgets as they're related:
std::map<std::string, PoseWidget*> pose_widget_map_;
std::map<std::string, EditButton*> edit_button_map_;

Eigen::Vector3d map_origin_;

// QT state:
QString namespace_;
QString planner_name_;
QString planning_budget_value_{"100.0"};
QString odometry_topic_;
bool align_terrain_on_load_{true};

// Other state:
std::string currently_editing_;
Expand Down
58 changes: 0 additions & 58 deletions snowsampler_rviz/include/snowsampler_rviz/pose_widget.h

This file was deleted.

50 changes: 0 additions & 50 deletions snowsampler_rviz/src/edit_button.cpp

This file was deleted.

Loading

0 comments on commit b2d4806

Please sign in to comment.