Public Member Functions | Private Types | Private Slots | Private Member Functions | Private Attributes | List of all members
robotiq_3f_rviz::Robotiq3FingerPanel Class Reference
Inheritance diagram for robotiq_3f_rviz::Robotiq3FingerPanel:
Inheritance graph
[legend]

Public Member Functions

 Robotiq3FingerPanel (QWidget *parent=nullptr)
 
- Public Member Functions inherited from rviz::Panel
virtual QString getClassId () const
 
virtual QString getDescription () const
 
virtual QString getName () const
 
void initialize (VisualizationManager *manager)
 
virtual void load (const Config &config)
 
virtual void onInitialize ()
 
 Panel (QWidget *parent=0)
 
virtual void save (Config config) const
 
virtual void setClassId (const QString &class_id)
 
virtual void setDescription (const QString &description)
 
virtual void setName (const QString &name)
 
virtual ~Panel ()
 

Private Types

typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput RQ3Fin
 
typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput RQ3Fout
 

Private Slots

void on_button_basic_clicked ()
 
void on_button_close_clicked ()
 
void on_button_off_clicked ()
 
void on_button_on_clicked ()
 
void on_button_open_clicked ()
 
void on_button_pinch_clicked ()
 
void on_button_scissor_clicked ()
 
void on_button_send_clicked ()
 
void on_button_wide_clicked ()
 
void on_check_send_clicked (const bool checked)
 
void on_slider_force_valueChanged (const int value)
 
void on_slider_position_valueChanged (const int value)
 
void on_slider_speed_valueChanged (const int value)
 

Private Member Functions

void auto_send_check ()
 
void on_status (const RQ3Fin &status)
 
void send ()
 
void set_button_active (QPushButton *button, const bool active)
 
void set_mode (const uint8_t mode)
 
void set_PRA (const uint8_t PRA)
 

Private Attributes

std::atomic_bool auto_send = ATOMIC_FLAG_INIT
 
RQ3Fout command
 
ros::NodeHandle n
 
ros::Publisher pub_command
 
ros::Subscriber sub_status
 
Ui::Robotiq3FingerForm ui
 

Additional Inherited Members

- Signals inherited from rviz::Panel
void configChanged ()
 
- Protected Attributes inherited from rviz::Panel
VisualizationManagervis_manager_
 

Detailed Description

Definition at line 10 of file robotiq_3f_rviz.cpp.

Member Typedef Documentation

typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput robotiq_3f_rviz::Robotiq3FingerPanel::RQ3Fin
private

Definition at line 43 of file robotiq_3f_rviz.cpp.

typedef robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput robotiq_3f_rviz::Robotiq3FingerPanel::RQ3Fout
private

Definition at line 42 of file robotiq_3f_rviz.cpp.

Constructor & Destructor Documentation

robotiq_3f_rviz::Robotiq3FingerPanel::Robotiq3FingerPanel ( QWidget *  parent = nullptr)

Definition at line 67 of file robotiq_3f_rviz.cpp.

Member Function Documentation

void robotiq_3f_rviz::Robotiq3FingerPanel::auto_send_check ( )
private

Definition at line 139 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_basic_clicked ( )
privateslot

Definition at line 95 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_close_clicked ( )
privateslot

Definition at line 105 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_off_clicked ( )
privateslot

Definition at line 89 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_on_clicked ( )
privateslot

Definition at line 80 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_open_clicked ( )
privateslot

Definition at line 103 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_pinch_clicked ( )
privateslot

Definition at line 99 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_scissor_clicked ( )
privateslot

Definition at line 101 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_send_clicked ( )
privateslot

Definition at line 76 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_button_wide_clicked ( )
privateslot

Definition at line 97 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_check_send_clicked ( const bool  checked)
privateslot

Definition at line 131 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_slider_force_valueChanged ( const int  value)
privateslot

Definition at line 111 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_slider_position_valueChanged ( const int  value)
privateslot

Definition at line 107 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_slider_speed_valueChanged ( const int  value)
privateslot

Definition at line 121 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::on_status ( const RQ3Fin status)
private

Definition at line 151 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::send ( )
private

Definition at line 137 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::set_button_active ( QPushButton *  button,
const bool  active 
)
private

Definition at line 174 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::set_mode ( const uint8_t  mode)
private

Definition at line 141 of file robotiq_3f_rviz.cpp.

void robotiq_3f_rviz::Robotiq3FingerPanel::set_PRA ( const uint8_t  PRA)
private

Definition at line 146 of file robotiq_3f_rviz.cpp.

Member Data Documentation

std::atomic_bool robotiq_3f_rviz::Robotiq3FingerPanel::auto_send = ATOMIC_FLAG_INIT
private

Definition at line 64 of file robotiq_3f_rviz.cpp.

RQ3Fout robotiq_3f_rviz::Robotiq3FingerPanel::command
private

Definition at line 62 of file robotiq_3f_rviz.cpp.

ros::NodeHandle robotiq_3f_rviz::Robotiq3FingerPanel::n
private

Definition at line 58 of file robotiq_3f_rviz.cpp.

ros::Publisher robotiq_3f_rviz::Robotiq3FingerPanel::pub_command
private

Definition at line 59 of file robotiq_3f_rviz.cpp.

ros::Subscriber robotiq_3f_rviz::Robotiq3FingerPanel::sub_status
private

Definition at line 60 of file robotiq_3f_rviz.cpp.

Ui::Robotiq3FingerForm robotiq_3f_rviz::Robotiq3FingerPanel::ui
private

Definition at line 56 of file robotiq_3f_rviz.cpp.


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


robotiq_3f_rviz
Author(s):
autogenerated on Tue Jun 1 2021 02:30:03