23 #ifndef open_manipulator_control_gui_QNODE_HPP_ 24 #define open_manipulator_control_gui_QNODE_HPP_ 37 #include <QStringListModel> 39 #include <sensor_msgs/JointState.h> 40 #include <std_msgs/String.h> 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" 48 #define NUM_OF_JOINT_AND_TOOL 5 63 QNode(
int argc,
char** argv );
80 void log(
const LogLevel &level,
const std::string &msg);
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);
std::vector< double > getPresentKinematicsPose()
void log(const LogLevel &level, const std::string &msg)
ros::Subscriber open_manipulator_kinematics_pose_sub_
bool getOpenManipulatorActuatorState()
ros::ServiceClient goal_tool_control_client_
ros::ServiceClient set_actuator_state_client_
std::vector< double > present_kinematic_position_
bool setTaskSpacePath(std::vector< double > kinematics_pose, double path_time)
ros::Subscriber open_manipulator_states_sub_
ros::Publisher open_manipulator_option_pub_
bool setJointSpacePath(std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
void jointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg)
void manipulatorStatesCallback(const open_manipulator_msgs::OpenManipulatorState::ConstPtr &msg)
bool open_manipulator_is_moving_
std::vector< double > present_joint_angle_
bool getOpenManipulatorMovingState()
ros::ServiceClient goal_joint_space_path_client_
QNode(int argc, char **argv)
bool setActuatorState(bool actuator_state)
QStringListModel * loggingModel()
ros::ServiceClient goal_task_space_path_position_only_client_
ros::ServiceClient goal_drawing_trajectory_client_
QStringListModel logging_model
bool setToolControl(std::vector< double > joint_angle)
void kinematicsPoseCallback(const open_manipulator_msgs::KinematicsPose::ConstPtr &msg)
open_manipulator_msgs::KinematicsPose kinematics_pose_
bool setDrawingTrajectory(std::string name, std::vector< double > arg, double path_time)
bool open_manipulator_actuator_enabled_
void setOption(std::string opt)
ros::Subscriber open_manipulator_joint_states_sub_
std::vector< double > getPresentJointAngle()