1 #ifndef RAM_QT_GUIS_MODIFY_HPP 2 #define RAM_QT_GUIS_MODIFY_HPP 8 #include <ram_display/UpdateSelection.h> 9 #include <ram_modify_trajectory/AddPoses.h> 10 #include <ram_modify_trajectory/DeleteSelectedPoses.h> 11 #include <ram_modify_trajectory/GetPosesFromLayer.h> 12 #include <ram_modify_trajectory/GetPosesFromLayersList.h> 13 #include <ram_modify_trajectory/GetPosesFromTrajectory.h> 14 #include <ram_modify_trajectory/ModifySelectedPoses.h> 15 #include <ram_modify_trajectory/ReflectSelectedPoses.h> 16 #include <ram_modify_trajectory/ResetSelectedPoses.h> 17 #include <ram_modify_trajectory/RotateSelectedPoses.h> 18 #include <ram_modify_trajectory/ScaleSelectedPoses.h> 19 #include <ram_msgs/AdditiveManufacturingTrajectory.h> 22 #include <ram_utils/GetLayerSize.h> 23 #include <ram_utils/GetNumberOfLayersLevels.h> 24 #include <ram_utils/GetTrajectorySize.h> 32 #include <QDialogButtonBox> 34 #include <QMessageBox> 35 #include <QPushButton> 36 #include <QRadioButton> 37 #include <QScrollArea> 40 #include <QVBoxLayout> 41 #include <QtConcurrent/QtConcurrentRun> 60 void trajReceived(
const ram_msgs::AdditiveManufacturingTrajectory::Ptr& msg);
63 bool delete_widgets =
true);
89 const QString message,
90 const QString info_msg);
QDoubleSpinBox * reflect_point_y_
ros::ServiceClient modify_selected_poses_client_
void selectionModeSelected()
QDoubleSpinBox * reflect_vector_y_
QDoubleSpinBox * reflect_point_x_
void changeGUIToRangeListSelection(const QString help_string, const unsigned min, const unsigned max)
void connectToService(ros::ServiceClient &client)
ros::ServiceClient reset_selected_poses_client_
void trajReceived(const ram_msgs::AdditiveManufacturingTrajectory::Ptr &msg)
ros::ServiceClient update_selection_client_
ros::ServiceClient get_poses_from_trajectory_client_
ModifyPoses * modify_poses_ui_
std::vector< unsigned > relative_indices_
void changeGUIToOperationSelection()
QDoubleSpinBox * rotation_point_y_
void changeGUIToRotatePoses()
void propagateSelection()
std::mutex trajectory_mutex_
void clearLayout(QLayout *layout, bool delete_widgets=true)
ros::ServiceClient get_poses_from_layer_client_
Modify(QWidget *parent=NULL)
std::vector< unsigned > layers_to_propagate_
void changeGUIToReflectPoses()
void save(rviz::Config config) const
QVector< QRadioButton * > selection_buttons_
QDoubleSpinBox * scale_factor_
std::vector< QRadioButton * > operations_
void updateTemporarySelection(std::vector< unsigned > selection)
ros::ServiceClient get_trajectory_size_client_
QDoubleSpinBox * scale_center_y_
void displayErrorBoxHandler(const QString title, const QString message, const QString info_msg)
ros::ServiceClient scale_selected_poses_client_
ros::ServiceClient rotate_selected_poses_client_
QDoubleSpinBox * rotation_point_x_
void load(const rviz::Config &config)
void changeGUIToSelectionMode()
double min(double a, double b)
ros::ServiceClient get_number_of_layers_client_
void displayErrorMessageBox(const QString, const QString, const QString)
std::vector< ram_msgs::AdditiveManufacturingPose > selected_poses_
void changeGUIToModifyPoses()
ros::ServiceClient get_layer_size_client_
ros::ServiceClient reflect_selected_poses_client_
ros::ServiceClient get_poses_from_layers_list_client_
ros::ServiceClient add_poses_client_
ros::ServiceClient delete_selected_poses_client_
std::vector< QRadioButton * > geometric_operations_
QDoubleSpinBox * reflect_vector_x_
void changeGUIToScalePoses()
QDoubleSpinBox * rotation_angle_
double max(double a, double b)
ram_display::UpdateSelection::Request selection
QDoubleSpinBox * scale_center_x_
ram_msgs::AdditiveManufacturingTrajectory trajectory_
ModifyRangeListSelection * range_list_selection_ui_