dsr_service_io_simple.cpp
Go to the documentation of this file.
1 /*
2  * [c++ example simple] I/O test for doosan robot
3  * Author: Jin Hyuk Gong (jinhyuk.gong@doosan.com)
4  *
5  * Copyright (c) 2019 Doosan Robotics
6  * Use of this source code is governed by the BSD, see LICENSE
7 */
8 
9 #include <ros/ros.h>
10 #include <signal.h>
11 
12 #include "dsr_util.h"
13 #include "dsr_robot.h"
14 
15 using namespace std;
16 using namespace DSR_Robot;
17 
18 //----- set tartget robot----------------------------------------------------
19 string ROBOT_ID = "dsr01";
20 string ROBOT_MODEL = "m1013";
21 void SET_ROBOT(string id, string model) {ROBOT_ID = id; ROBOT_MODEL= model;}
22 //---------------------------------------------------------------------------
23 
25 
26 void msgRobotState_cb(const dsr_msgs::RobotState::ConstPtr& msg)
27 {
28  static int sn_cnt =0;
29 
30  sn_cnt++;
31  if(0==(sn_cnt % 100))
32  {
33  ROS_INFO("________ ROBOT STATUS ________");
34  ROS_INFO(" robot_state : %d", msg->robot_state);
35  ROS_INFO(" robot_state_str : %s", msg->robot_state_str.c_str());
36  ROS_INFO(" current_posj : %7.3f %7.3f %7.3f %7.3f %7.3f %7.3f",msg->current_posj[0] ,msg->current_posj[1] ,msg->current_posj[2]
37  ,msg->current_posj[3] ,msg->current_posj[4] ,msg->current_posj[5] );
38  ROS_INFO(" io_control_box : %d", msg->io_control_box);
39  //ROS_INFO(" io_modbus : %d", msg->io_modbus);
40  //ROS_INFO(" error : %d", msg->error);
41  ROS_INFO(" access_control : %d", msg->access_control);
42  ROS_INFO(" homming_completed : %d", msg->homming_completed);
43  ROS_INFO(" tp_initialized : %d", msg->tp_initialized);
44  ROS_INFO(" speed : %d", msg->speed);
45  ROS_INFO(" mastering_need : %d", msg->mastering_need);
46  ROS_INFO(" drl_stopped : %d", msg->drl_stopped);
47  ROS_INFO(" disconnected : %d", msg->disconnected);
48  }
49 }
50 
51 static void thread_subscriber()
52 {
53  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
56  ros::MultiThreadedSpinner spinner(2);
57  spinner.spin();
58 }
59 
60 void SigHandler(int sig)
61 {
62  // Do some custom action.
63  // For example, publish a stop message to some other nodes.
64 
65  // All the default sigint handler does is call shutdown()
66  ROS_INFO("shutdown time!");
67  ROS_INFO("shutdown time!");
68  ROS_INFO("shutdown time!");
69  //ros::ServiceClient srvMoveStop = nh.serviceClient<dsr_msgs::MoveStop>("/dsr01m1013/motion/move_stop");
70 
71  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
72  ros::Publisher pubRobotStop = node->advertise<dsr_msgs::RobotStop>("/"+ROBOT_ID +ROBOT_MODEL+"/stop",100);
73 
74  dsr_msgs::RobotStop msg;
75 
76  msg.stop_mode = STOP_TYPE_QUICK;
77  pubRobotStop.publish(msg);
78 
79  ros::shutdown();
80 }
81 
82 int main(int argc, char** argv)
83 {
84  //----- set target robot ---------------
85  string my_robot_id = "dsr01";
86  string my_robot_model = "m1013";
87  if(1 == argc){
88  ROS_INFO("default arguments: dsr01 m1013");
89  }
90  else{
91  if(3 != argc){
92  ROS_ERROR("invalid arguments: <ns> <model> (ex) dsr01 m1013");
93  exit(1);
94  }
95  for (int i = 1; i < argc; i++){
96  printf("argv[%d] = %s\n", i, argv[i]);
97  }
98  my_robot_id = argv[1];
99  my_robot_model = argv[2];
100  }
101  //std::cout << "my_robot_id= " << my_robot_id << ", my_robot_model= " << my_robot_model << endl;
102  SET_ROBOT(my_robot_id, my_robot_model);
103 
104  //----- init ROS ----------------------
105  ros::init(argc, argv, "dsr_service_test_cpp", ros::init_options::NoSigintHandler);
106  ros::NodeHandle nh("~");
107  // Override the default ros sigint handler.
108  // This must be set after the first NodeHandle is created.
109  signal(SIGINT, SigHandler);
110  ros::Publisher pubRobotStop = nh.advertise<dsr_msgs::RobotStop>("/"+ROBOT_ID +ROBOT_MODEL+"/stop",10);
112 
113  //----- create DsrRobot ---------------
114  CDsrRobot robot(nh, my_robot_id, my_robot_model);
115 
116  // run subscriber thread (for monitoring)
117  boost::thread thread_sub(thread_subscriber);
118 
120  robot.set_digital_output(2, true);
121  if(robot.get_digital_input(2) == 1){
122  robot.set_digital_output(11, true);
123  }
124 
125  while(ros::ok())
126  {
127  }
128  thread_sub.join();
129  // wait the second thread to finish
130  ROS_INFO("dsr_service_test finished !!!!!!!!!!!!!!!!!!!!!");
131  return 0;
132 }
int main(int argc, char **argv)
string ROBOT_ID
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void msgRobotState_cb(const dsr_msgs::RobotState::ConstPtr &msg)
void SigHandler(int sig)
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void shutdown()
void SET_ROBOT(string id, string model)
static void thread_subscriber()
#define ROS_ERROR(...)
string ROBOT_MODEL


cpp
Author(s): Kab Kyoum Kim , Jin Hyuk Gong , Jeongwoo Lee
autogenerated on Thu Jun 20 2019 19:43:26