dynamixel_workbench_wheel.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright (c) 2016, ROBOTIS CO., LTD.
3 * All rights reserved.
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions are met:
7 *
8 * * Redistributions of source code must retain the above copyright notice, this
9 * list of conditions and the following disclaimer.
10 *
11 * * Redistributions in binary form must reproduce the above copyright notice,
12 * this list of conditions and the following disclaimer in the documentation
13 * and/or other materials provided with the distribution.
14 *
15 * * Neither the name of ROBOTIS nor the names of its
16 * contributors may be used to endorse or promote products derived from
17 * this software without specific prior written permission.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 *******************************************************************************/
30 
31 /* Author: Taehoon Lim (Darby) */
32 
34 
35 using namespace dynamixel_workbench_wheel;
36 
38  :nh_priv_("~"),
39  is_debug_(false)
40 {
41  // Init parameter
42  nh_priv_.param("is_debug", is_debug_, is_debug_);
43 
44  // Init target name
46 
47  // init ROS Client
48  wheel_control_client_ = nh_.serviceClient<dynamixel_workbench_msgs::SetDirection>("/dynamixel_workbench_tutorials/wheel");
49 }
50 
52 {
54 }
55 
57 {
58  ROS_INFO("dynamixel_workbench_wheel : Init OK!");
59  return true;
60 }
61 
63 {
64  ros::shutdown();
65  return true;
66 }
67 
69 {
70  struct termios oldt, newt;
71  int ch;
72 
73  tcgetattr( STDIN_FILENO, &oldt );
74  newt = oldt;
75  newt.c_lflag &= ~(ICANON | ECHO);
76  newt.c_cc[VMIN] = 0;
77  newt.c_cc[VTIME] = 1;
78  tcsetattr( STDIN_FILENO, TCSANOW, &newt );
79  ch = getchar();
80  tcsetattr( STDIN_FILENO, TCSANOW, &oldt );
81 
82  return ch;
83 }
84 
86 {
87  struct termios oldt, newt;
88  int ch;
89  int oldf;
90 
91  tcgetattr(STDIN_FILENO, &oldt);
92  newt = oldt;
93  newt.c_lflag &= ~(ICANON | ECHO);
94  tcsetattr(STDIN_FILENO, TCSANOW, &newt);
95  oldf = fcntl(STDIN_FILENO, F_GETFL, 0);
96  fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK);
97 
98  ch = getchar();
99 
100  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
101  fcntl(STDIN_FILENO, F_SETFL, oldf);
102 
103  if (ch != EOF)
104  {
105  ungetc(ch, stdin);
106  return 1;
107  }
108  return 0;
109 }
110 
111 int main(int argc, char **argv)
112 {
113  // Init ROS node
114  ros::init(argc, argv, "dynamixel_workbench_wheel");
115  ROS_INFO("Set angular velocity(+-0.2 rad/sec) to your motor!! by using keyboard");
116  ROS_INFO("w : Forward");
117  ROS_INFO("x : Backward");
118  ROS_INFO("a : Left");
119  ROS_INFO("d : Right");
120  ROS_INFO("s : STOPS\n");
121  ROS_INFO("ESC : exit");
122 
123  DynamixelWorkbenchWheel dynamixel_wheel;
124  dynamixel_workbench_msgs::SetDirection srv;
125  ros::Rate loop_rate(125);
126 
127  while(1)
128  {
129  if (dynamixel_wheel.kbhit())
130  {
131  char c = dynamixel_wheel.getch();
132 
133  if (c == ESC_ASCII_VALUE)
134  {
135  break;
136  }
137 
138  if (c == FORWARD)
139  {
140  srv.request.right_wheel_velocity = 0.2;
141  srv.request.left_wheel_velocity = 0.2;
142  }
143  else if (c == BACKWARD)
144  {
145  srv.request.right_wheel_velocity = -0.2;
146  srv.request.left_wheel_velocity = -0.2;
147  }
148  else if (c == LEFT)
149  {
150  srv.request.right_wheel_velocity = 0.2;
151  srv.request.left_wheel_velocity = -0.2;
152  }
153  else if (c == RIGHT)
154  {
155  srv.request.right_wheel_velocity = -0.2;
156  srv.request.left_wheel_velocity = 0.2;
157  }
158  else if (c == STOPS)
159  {
160  srv.request.right_wheel_velocity = 0.0;
161  srv.request.left_wheel_velocity = 0.0;
162  }
163  else
164  {
165  srv.request.right_wheel_velocity = 0.2;
166  srv.request.left_wheel_velocity = 0.2;
167  }
168 
169  if (dynamixel_wheel.wheel_control_client_.call(srv))
170  {
171  sleep(0.8);
172  ROS_INFO("[LEFT_WHEEL_VELOCITY]: %.2f, [RIGHT_WHEEL_VELOCITY]: %.2f", srv.response.left_wheel_velocity, srv.response.right_wheel_velocity);
173  }
174  else
175  {
176  sleep(0.8);
177  ROS_ERROR("Failed to call service /wheel");
178  }
179  }
180 
181  ros::spinOnce();
182  loop_rate.sleep();
183  }
184  return 0;
185 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
#define FORWARD
#define STOPS
#define RIGHT
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
int main(int argc, char **argv)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ESC_ASCII_VALUE
bool sleep()
ROSCPP_DECL void shutdown()
#define ROS_ASSERT(cond)
#define BACKWARD
#define LEFT
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)


dynamixel_workbench_tutorials
Author(s): Darby Lim
autogenerated on Thu May 25 2017 02:38:50