qnode.hpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Darby Lim, Hye-Jong KIM, Ryan Shim, Yong-Ho Na */
18 
19 /*****************************************************************************
20 ** Ifdefs
21 *****************************************************************************/
22 
23 #ifndef open_manipulator_control_gui_QNODE_HPP_
24 #define open_manipulator_control_gui_QNODE_HPP_
25 
26 /*****************************************************************************
27 ** Includes
28 *****************************************************************************/
29 
30 // To workaround boost/qt4 problems that won't be bugfixed. Refer to
31 // https://bugreports.qt.io/browse/QTBUG-22829
32 #ifndef Q_MOC_RUN
33 #include <ros/ros.h>
34 #endif
35 #include <string>
36 #include <QThread>
37 #include <QStringListModel>
38 
39 #include <sensor_msgs/JointState.h>
40 #include <std_msgs/String.h>
41 
42 #include "open_manipulator_msgs/OpenManipulatorState.h"
43 #include "open_manipulator_msgs/SetJointPosition.h"
44 #include "open_manipulator_msgs/SetKinematicsPose.h"
45 #include "open_manipulator_msgs/SetDrawingTrajectory.h"
46 #include "open_manipulator_msgs/SetActuatorState.h"
47 
48 #define NUM_OF_JOINT_AND_TOOL 5
49 
50 /*****************************************************************************
51 ** Namespaces
52 *****************************************************************************/
53 
55 
56 /*****************************************************************************
57 ** Class
58 *****************************************************************************/
59 
60 class QNode : public QThread {
61  Q_OBJECT
62 public:
63  QNode(int argc, char** argv );
64  virtual ~QNode();
65  bool init();
66  void run();
67 
68  /*********************
69  ** Logging
70  **********************/
71  enum LogLevel {
77  };
78 
79  QStringListModel* loggingModel() { return &logging_model; }
80  void log( const LogLevel &level, const std::string &msg);
81 
82  void manipulatorStatesCallback(const open_manipulator_msgs::OpenManipulatorState::ConstPtr &msg);
83  void jointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg);
84  void kinematicsPoseCallback(const open_manipulator_msgs::KinematicsPose::ConstPtr &msg);
85 
86  std::vector<double> getPresentJointAngle();
87  std::vector<double> getPresentKinematicsPose();
90 
91  void setOption(std::string opt);
92  bool setJointSpacePath(std::vector<std::string> joint_name, std::vector<double> joint_angle, double path_time);
93  bool setTaskSpacePath(std::vector<double> kinematics_pose, double path_time);
94  bool setDrawingTrajectory(std::string name, std::vector<double> arg, double path_time);
95  bool setToolControl(std::vector<double> joint_angle);
96  bool setActuatorState(bool actuator_state);
97 
98 Q_SIGNALS:
99  void rosShutdown();
100 
101 private:
103  char** init_argv;
104  QStringListModel logging_model;
105 
107 
111 
117 
118  std::vector<double> present_joint_angle_;
119  std::vector<double> present_kinematic_position_;
120  open_manipulator_msgs::KinematicsPose kinematics_pose_;
121 
124 };
125 
126 } // namespace open_manipulator_control_gui
127 
128 #endif /* open_manipulator_control_gui_QNODE_HPP_ */
std::vector< double > getPresentKinematicsPose()
Definition: qnode.cpp:133
void log(const LogLevel &level, const std::string &msg)
ros::Subscriber open_manipulator_kinematics_pose_sub_
Definition: qnode.hpp:110
ros::ServiceClient goal_tool_control_client_
Definition: qnode.hpp:114
ros::ServiceClient set_actuator_state_client_
Definition: qnode.hpp:115
std::vector< double > present_kinematic_position_
Definition: qnode.hpp:119
bool setTaskSpacePath(std::vector< double > kinematics_pose, double path_time)
Definition: qnode.cpp:167
ros::Subscriber open_manipulator_states_sub_
Definition: qnode.hpp:108
ros::Publisher open_manipulator_option_pub_
Definition: qnode.hpp:106
bool setJointSpacePath(std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
Definition: qnode.cpp:153
void jointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg)
Definition: qnode.cpp:102
void manipulatorStatesCallback(const open_manipulator_msgs::OpenManipulatorState::ConstPtr &msg)
Definition: qnode.cpp:90
std::vector< double > present_joint_angle_
Definition: qnode.hpp:118
ros::ServiceClient goal_joint_space_path_client_
Definition: qnode.hpp:112
QNode(int argc, char **argv)
Definition: qnode.cpp:40
bool setActuatorState(bool actuator_state)
Definition: qnode.cpp:220
QStringListModel * loggingModel()
Definition: qnode.hpp:79
ros::ServiceClient goal_task_space_path_position_only_client_
Definition: qnode.hpp:113
ros::ServiceClient goal_drawing_trajectory_client_
Definition: qnode.hpp:116
QStringListModel logging_model
Definition: qnode.hpp:104
bool setToolControl(std::vector< double > joint_angle)
Definition: qnode.cpp:207
void kinematicsPoseCallback(const open_manipulator_msgs::KinematicsPose::ConstPtr &msg)
Definition: qnode.cpp:117
open_manipulator_msgs::KinematicsPose kinematics_pose_
Definition: qnode.hpp:120
bool setDrawingTrajectory(std::string name, std::vector< double > arg, double path_time)
Definition: qnode.cpp:191
void setOption(std::string opt)
Definition: qnode.cpp:146
ros::Subscriber open_manipulator_joint_states_sub_
Definition: qnode.hpp:109
std::vector< double > getPresentJointAngle()
Definition: qnode.cpp:129


open_manipulator_control_gui
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Mon Jun 10 2019 14:11:52