26 #include <std_msgs/String.h> 28 #include "../include/open_manipulator_control_gui/qnode.hpp" 43 open_manipulator_actuator_enabled_(false),
44 open_manipulator_is_moving_(false)
86 std::cout <<
"Ros shutdown, proceeding to close the gui." << std::endl;
92 if(msg->open_manipulator_moving_state == msg->IS_MOVING)
97 if(msg->open_manipulator_actuator_state == msg->ACTUATOR_ENABLED)
104 std::vector<double> temp_angle;
106 for(
int i = 0; i < msg->name.size(); i ++)
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));
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);
148 std_msgs::String msg;
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;
162 return srv.response.is_planned;
169 open_manipulator_msgs::SetKinematicsPose srv;
171 srv.request.end_effector_name =
"gripper";
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);
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;
182 srv.request.path_time = path_time;
186 return srv.response.is_planned;
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));
202 return srv.response.is_planned;
209 open_manipulator_msgs::SetJointPosition srv;
210 srv.request.joint_position.joint_name.push_back(
"gripper");
211 srv.request.joint_position.position = joint_angle;
215 return srv.response.is_planned;
222 open_manipulator_msgs::SetActuatorState srv;
223 srv.request.set_actuator_state = actuator_state;
227 return srv.response.is_planned;
std::vector< double > getPresentKinematicsPose()
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
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_
bool getOpenManipulatorActuatorState()
ros::ServiceClient goal_tool_control_client_
ros::ServiceClient set_actuator_state_client_
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_
bool setTaskSpacePath(std::vector< double > kinematics_pose, double path_time)
ros::Subscriber open_manipulator_states_sub_
#define NUM_OF_JOINT_AND_TOOL
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)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceClient goal_task_space_path_position_only_client_
ros::ServiceClient goal_drawing_trajectory_client_
bool setToolControl(std::vector< double > joint_angle)
ROSCPP_DECL bool isStarted()
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)
ROSCPP_DECL void shutdown()
bool open_manipulator_actuator_enabled_
ROSCPP_DECL void spinOnce()
void setOption(std::string opt)
ros::Subscriber open_manipulator_joint_states_sub_
std::vector< double > getPresentJointAngle()
ROSCPP_DECL void waitForShutdown()