13 #include "dsr_robot.h" 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);
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);
74 dsr_msgs::RobotStop msg;
76 msg.stop_mode = STOP_TYPE_QUICK;
77 pubRobotStop.publish(msg);
82 int main(
int argc,
char** argv)
85 string my_robot_id =
"dsr01";
86 string my_robot_model =
"m1013";
88 ROS_INFO(
"default arguments: dsr01 m1013");
92 ROS_ERROR(
"invalid arguments: <ns> <model> (ex) dsr01 m1013");
95 for (
int i = 1; i < argc; i++){
96 printf(
"argv[%d] = %s\n", i, argv[i]);
98 my_robot_id = argv[1];
99 my_robot_model = argv[2];
114 CDsrRobot robot(nh, my_robot_id, my_robot_model);
120 robot.set_digital_output(2,
true);
121 if(robot.get_digital_input(2) == 1){
122 robot.set_digital_output(11,
true);
130 ROS_INFO(
"dsr_service_test finished !!!!!!!!!!!!!!!!!!!!!");
int main(int argc, char **argv)
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)
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()