Signals | Public Member Functions | Protected Slots | Protected Attributes | List of all members
fanuc_grinding_rviz_plugin::PostProcessorWidget Class Reference

#include <post_processor_widget.h>

Inheritance diagram for fanuc_grinding_rviz_plugin::PostProcessorWidget:
Inheritance graph
[legend]

Signals

void enablePanel (const bool)
 
void getRobotTrajectoryData ()
 
void guiChanged ()
 
void sendMsgBox (const QString title, const QString msg, const QString info_msg)
 
void sendStatus (const QString status)
 

Public Member Functions

void load (const rviz::Config &config)
 
 PostProcessorWidget (QWidget *parent=NULL)
 
void save (rviz::Config config)
 
void setIsGrindingPose (const std::vector< bool > &is_grinding_pose)
 
void setPostProcessorParams (const fanuc_grinding_post_processor::PostProcessorService::Request &params)
 
void setProgramLocation (const std::string &location)
 
void setRobotPoses (const std::vector< geometry_msgs::Pose > &robot_poses)
 

Protected Slots

void connectToServices ()
 
void generateProgram ()
 
void generateProgramButtonHandler ()
 
void setIpAddressEnable (const int state)
 
void triggerSave ()
 
void tweakProgramName ()
 
void updateGUI ()
 
void updateInternalValues ()
 

Protected Attributes

QLineEdit * comment_
 
QSpinBox * extrication_speed_
 
QPushButton * generate_program_button_
 
QLineEdit * ip_address_
 
QLabel * ip_adress_label_
 
QSpinBox * machining_speed_
 
ros::NodeHandle nh_
 
ros::ServiceClient post_processor_service_
 
QLineEdit * program_location_
 
QLineEdit * program_name_
 
fanuc_grinding_post_processor::PostProcessorService srv_post_processor_
 
QSpinBox * trajectory_z_offset_
 
QCheckBox * upload_program_
 

Detailed Description

Definition at line 20 of file post_processor_widget.h.

Constructor & Destructor Documentation

fanuc_grinding_rviz_plugin::PostProcessorWidget::PostProcessorWidget ( QWidget *  parent = NULL)

Definition at line 13 of file post_processor_widget.cpp.

Member Function Documentation

void fanuc_grinding_rviz_plugin::PostProcessorWidget::connectToServices ( )
protectedslot

Definition at line 245 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::enablePanel ( const bool  )
signal
void fanuc_grinding_rviz_plugin::PostProcessorWidget::generateProgram ( )
protectedslot

Definition at line 222 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::generateProgramButtonHandler ( )
protectedslot

Definition at line 204 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::getRobotTrajectoryData ( )
signal
void fanuc_grinding_rviz_plugin::PostProcessorWidget::guiChanged ( )
signal
void fanuc_grinding_rviz_plugin::PostProcessorWidget::load ( const rviz::Config config)

Definition at line 286 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::save ( rviz::Config  config)

Definition at line 273 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::sendMsgBox ( const QString  title,
const QString  msg,
const QString  info_msg 
)
signal
void fanuc_grinding_rviz_plugin::PostProcessorWidget::sendStatus ( const QString  status)
signal
void fanuc_grinding_rviz_plugin::PostProcessorWidget::setIpAddressEnable ( const int  state)
protectedslot

Definition at line 172 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::setIsGrindingPose ( const std::vector< bool > &  is_grinding_pose)

Definition at line 195 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::setPostProcessorParams ( const fanuc_grinding_post_processor::PostProcessorService::Request &  params)

Definition at line 118 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::setProgramLocation ( const std::string &  location)

Definition at line 178 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::setRobotPoses ( const std::vector< geometry_msgs::Pose > &  robot_poses)

Definition at line 184 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::triggerSave ( )
protectedslot

Definition at line 112 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::tweakProgramName ( )
protectedslot

Definition at line 159 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::updateGUI ( )
protectedslot

Definition at line 135 of file post_processor_widget.cpp.

void fanuc_grinding_rviz_plugin::PostProcessorWidget::updateInternalValues ( )
protectedslot

Definition at line 147 of file post_processor_widget.cpp.

Member Data Documentation

QLineEdit* fanuc_grinding_rviz_plugin::PostProcessorWidget::comment_
protected

Definition at line 55 of file post_processor_widget.h.

QSpinBox* fanuc_grinding_rviz_plugin::PostProcessorWidget::extrication_speed_
protected

Definition at line 57 of file post_processor_widget.h.

QPushButton* fanuc_grinding_rviz_plugin::PostProcessorWidget::generate_program_button_
protected

Definition at line 63 of file post_processor_widget.h.

QLineEdit* fanuc_grinding_rviz_plugin::PostProcessorWidget::ip_address_
protected

Definition at line 61 of file post_processor_widget.h.

QLabel* fanuc_grinding_rviz_plugin::PostProcessorWidget::ip_adress_label_
protected

Definition at line 60 of file post_processor_widget.h.

QSpinBox* fanuc_grinding_rviz_plugin::PostProcessorWidget::machining_speed_
protected

Definition at line 56 of file post_processor_widget.h.

ros::NodeHandle fanuc_grinding_rviz_plugin::PostProcessorWidget::nh_
protected

Definition at line 50 of file post_processor_widget.h.

ros::ServiceClient fanuc_grinding_rviz_plugin::PostProcessorWidget::post_processor_service_
protected

Definition at line 51 of file post_processor_widget.h.

QLineEdit* fanuc_grinding_rviz_plugin::PostProcessorWidget::program_location_
protected

Definition at line 62 of file post_processor_widget.h.

QLineEdit* fanuc_grinding_rviz_plugin::PostProcessorWidget::program_name_
protected

Definition at line 54 of file post_processor_widget.h.

fanuc_grinding_post_processor::PostProcessorService fanuc_grinding_rviz_plugin::PostProcessorWidget::srv_post_processor_
protected

Definition at line 52 of file post_processor_widget.h.

QSpinBox* fanuc_grinding_rviz_plugin::PostProcessorWidget::trajectory_z_offset_
protected

Definition at line 58 of file post_processor_widget.h.

QCheckBox* fanuc_grinding_rviz_plugin::PostProcessorWidget::upload_program_
protected

Definition at line 59 of file post_processor_widget.h.


The documentation for this class was generated from the following files:


rviz_plugin
Author(s): Kévin Bolloré, Victor Lamoine - Institut Maupertuis
autogenerated on Thu Dec 19 2019 03:38:28