qnode.cpp
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 ** Includes
21 *****************************************************************************/
22 
23 #include <ros/ros.h>
24 #include <ros/network.h>
25 #include <string>
26 #include <std_msgs/String.h>
27 #include <sstream>
28 #include "../include/open_manipulator_control_gui/qnode.hpp"
29 
30 /*****************************************************************************
31 ** Namespaces
32 *****************************************************************************/
33 
35 
36 /*****************************************************************************
37 ** Implementation
38 *****************************************************************************/
39 
40 QNode::QNode(int argc, char** argv ) :
41  init_argc(argc),
42  init_argv(argv),
43  open_manipulator_actuator_enabled_(false),
44  open_manipulator_is_moving_(false)
45  {}
46 
48  if(ros::isStarted()) {
49  ros::shutdown(); // explicitly needed since we use ros::start();
51  }
52  wait();
53 }
54 
55 bool QNode::init() {
56  ros::init(init_argc,init_argv,"open_manipulator_control_gui");
57  if ( ! ros::master::check() ) {
58  return false;
59  }
60  ros::start(); // explicitly needed since our nodehandle is going out of scope.
61  ros::NodeHandle n("");
62 
63  // msg publisher
64  open_manipulator_option_pub_ = n.advertise<std_msgs::String>("option", 10);
65  // msg subscriber
69  // service client
70  goal_joint_space_path_client_ = n.serviceClient<open_manipulator_msgs::SetJointPosition>("goal_joint_space_path");
71  goal_task_space_path_position_only_client_ = n.serviceClient<open_manipulator_msgs::SetKinematicsPose>("goal_task_space_path_position_only");
72  goal_tool_control_client_ = n.serviceClient<open_manipulator_msgs::SetJointPosition>("goal_tool_control");
73  set_actuator_state_client_ = n.serviceClient<open_manipulator_msgs::SetActuatorState>("set_actuator_state");
74  goal_drawing_trajectory_client_ = n.serviceClient<open_manipulator_msgs::SetDrawingTrajectory>("goal_drawing_trajectory");
75 
76  start();
77  return true;
78 }
79 
80 void QNode::run() {
81  ros::Rate loop_rate(10);
82  while ( ros::ok() ) {
83  ros::spinOnce();
84  loop_rate.sleep();
85  }
86  std::cout << "Ros shutdown, proceeding to close the gui." << std::endl;
87  Q_EMIT rosShutdown();
88 }
89 
90 void QNode::manipulatorStatesCallback(const open_manipulator_msgs::OpenManipulatorState::ConstPtr &msg)
91 {
92  if(msg->open_manipulator_moving_state == msg->IS_MOVING)
94  else
96 
97  if(msg->open_manipulator_actuator_state == msg->ACTUATOR_ENABLED)
99  else
101 }
102 void QNode::jointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg)
103 {
104  std::vector<double> temp_angle;
105  temp_angle.resize(NUM_OF_JOINT_AND_TOOL);
106  for(int i = 0; i < msg->name.size(); i ++)
107  {
108  if(!msg->name.at(i).compare("joint1")) temp_angle.at(0) = (msg->position.at(i));
109  else if(!msg->name.at(i).compare("joint2")) temp_angle.at(1) = (msg->position.at(i));
110  else if(!msg->name.at(i).compare("joint3")) temp_angle.at(2) = (msg->position.at(i));
111  else if(!msg->name.at(i).compare("joint4")) temp_angle.at(3) = (msg->position.at(i));
112  else if(!msg->name.at(i).compare("gripper")) temp_angle.at(4) = (msg->position.at(i));
113  }
114  present_joint_angle_ = temp_angle;
115 }
116 
117 void QNode::kinematicsPoseCallback(const open_manipulator_msgs::KinematicsPose::ConstPtr &msg)
118 {
119  std::vector<double> temp_position;
120  temp_position.push_back(msg->pose.position.x);
121  temp_position.push_back(msg->pose.position.y);
122  temp_position.push_back(msg->pose.position.z);
123 
124  present_kinematic_position_ = temp_position;
125 
126  kinematics_pose_.pose = msg->pose;
127 }
128 
129 std::vector<double> QNode::getPresentJointAngle()
130 {
131  return present_joint_angle_;
132 }
133 std::vector<double> QNode::getPresentKinematicsPose()
134 {
136 }
138 {
140 }
142 {
144 }
145 
146 void QNode::setOption(std::string opt)
147 {
148  std_msgs::String msg;
149  msg.data = opt;
151 }
152 
153 bool QNode::setJointSpacePath(std::vector<std::string> joint_name, std::vector<double> joint_angle, double path_time)
154 {
155  open_manipulator_msgs::SetJointPosition srv;
156  srv.request.joint_position.joint_name = joint_name;
157  srv.request.joint_position.position = joint_angle;
158  srv.request.path_time = path_time;
159 
161  {
162  return srv.response.is_planned;
163  }
164  return false;
165 }
166 
167 bool QNode::setTaskSpacePath(std::vector<double> kinematics_pose, double path_time)
168 {
169  open_manipulator_msgs::SetKinematicsPose srv;
170 
171  srv.request.end_effector_name = "gripper";
172 
173  srv.request.kinematics_pose.pose.position.x = kinematics_pose.at(0);
174  srv.request.kinematics_pose.pose.position.y = kinematics_pose.at(1);
175  srv.request.kinematics_pose.pose.position.z = kinematics_pose.at(2);
176 
177  srv.request.kinematics_pose.pose.orientation.w = kinematics_pose_.pose.orientation.w;
178  srv.request.kinematics_pose.pose.orientation.x = kinematics_pose_.pose.orientation.x;
179  srv.request.kinematics_pose.pose.orientation.y = kinematics_pose_.pose.orientation.y;
180  srv.request.kinematics_pose.pose.orientation.z = kinematics_pose_.pose.orientation.z;
181 
182  srv.request.path_time = path_time;
183 
185  {
186  return srv.response.is_planned;
187  }
188  return false;
189 }
190 
191 bool QNode::setDrawingTrajectory(std::string name, std::vector<double> arg, double path_time)
192 {
193  open_manipulator_msgs::SetDrawingTrajectory srv;
194  srv.request.end_effector_name = "gripper";
195  srv.request.drawing_trajectory_name = name;
196  srv.request.path_time = path_time;
197  for(int i = 0; i < arg.size(); i ++)
198  srv.request.param.push_back(arg.at(i));
199 
201  {
202  return srv.response.is_planned;
203  }
204  return false;
205 }
206 
207 bool QNode::setToolControl(std::vector<double> joint_angle)
208 {
209  open_manipulator_msgs::SetJointPosition srv;
210  srv.request.joint_position.joint_name.push_back("gripper");
211  srv.request.joint_position.position = joint_angle;
212 
214  {
215  return srv.response.is_planned;
216  }
217  return false;
218 }
219 
220 bool QNode::setActuatorState(bool actuator_state)
221 {
222  open_manipulator_msgs::SetActuatorState srv;
223  srv.request.set_actuator_state = actuator_state;
224 
226  {
227  return srv.response.is_planned;
228  }
229  return false;
230 }
231 
232 
233 } // namespace open_manipulator_control_gui
std::vector< double > getPresentKinematicsPose()
Definition: qnode.cpp:133
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL bool check()
ROSCPP_DECL void start()
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
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
#define NUM_OF_JOINT_AND_TOOL
Definition: qnode.hpp:48
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
ROSCPP_DECL bool ok()
QNode(int argc, char **argv)
Definition: qnode.cpp:40
bool setActuatorState(bool actuator_state)
Definition: qnode.cpp:220
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceClient goal_task_space_path_position_only_client_
Definition: qnode.hpp:113
bool sleep()
ros::ServiceClient goal_drawing_trajectory_client_
Definition: qnode.hpp:116
bool setToolControl(std::vector< double > joint_angle)
Definition: qnode.cpp:207
ROSCPP_DECL bool isStarted()
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
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()
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
ROSCPP_DECL void waitForShutdown()


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