towr_user_interface.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
31 
32 #include <ncurses.h>
33 
34 #include <xpp_states/convert.h>
35 
36 #include <towr_ros/TowrCommand.h>
37 #include <towr_ros/topic_names.h>
41 
42 
43 namespace towr {
44 
45 
49 static constexpr int Y_STATUS = END+1;
50 static constexpr int X_KEY = 1;
51 static constexpr int X_DESCRIPTION = 10;
52 static constexpr int X_VALUE = 35;
53 
54 
56 {
57  printw(" ******************************************************************************\n");
58  printw(" TOWR user interface (v1.4) \n");
59  printw(" \u00a9 Alexander W. Winkler \n");
60  printw(" https://github.com/ethz-adrl/towr\n");
61  printw(" ******************************************************************************\n\n");
62 
64  user_command_pub_ = n.advertise<towr_ros::TowrCommand>(towr_msgs::user_command, 1);
65 
66  goal_geom_.lin.p_.setZero();
67  goal_geom_.lin.p_ << 2.1, 0.0, 0.0;
68  goal_geom_.ang.p_ << 0.0, 0.0, 0.0; // roll, pitch, yaw angle applied Z->Y'->X''
69 
73  total_duration_ = 2.4;
74  visualize_trajectory_ = false;
75  plot_trajectory_ = false;
76  replay_speed_ = 1.0; // realtime
77  optimize_ = false;
80 
81  PrintScreen();
82 }
83 
84 void
86 {
87  wmove(stdscr, HEADING, X_KEY);
88  printw("Key");
89  wmove(stdscr, HEADING, X_DESCRIPTION);
90  printw("Description");
91  wmove(stdscr, HEADING, X_VALUE);
92  printw("Info");
93 
94  wmove(stdscr, OPTIMIZE, X_KEY);
95  printw("o");
96  wmove(stdscr, OPTIMIZE, X_DESCRIPTION);
97  printw("Optimize motion");
98  wmove(stdscr, OPTIMIZE, X_VALUE);
99  printw("-");
100 
101  wmove(stdscr, VISUALIZE, X_KEY);
102  printw("v");
103  wmove(stdscr, VISUALIZE, X_DESCRIPTION);
104  printw("visualize motion in rviz");
105  wmove(stdscr, VISUALIZE, X_VALUE);
106  printw("-");
107 
108  wmove(stdscr, INITIALIZATION, X_KEY);
109  printw("i");
110  wmove(stdscr, INITIALIZATION, X_DESCRIPTION);
111  printw("play initialization");
112  wmove(stdscr, INITIALIZATION, X_VALUE);
113  printw("-");
114 
115  wmove(stdscr, PLOT, X_KEY);
116  printw("p");
117  wmove(stdscr, PLOT, X_DESCRIPTION);
118  printw("Plot values (rqt_bag)");
119  wmove(stdscr, PLOT, X_VALUE);
120  printw("-");
121 
122  wmove(stdscr, REPLAY_SPEED, X_KEY);
123  printw(";/'");
124  wmove(stdscr, REPLAY_SPEED, X_DESCRIPTION);
125  printw("Replay speed");
126  wmove(stdscr, REPLAY_SPEED, X_VALUE);
127  printw("%.2f", replay_speed_);
128 
129  wmove(stdscr, GOAL_POS, X_KEY);
130  printw("arrows");
131  wmove(stdscr, GOAL_POS, X_DESCRIPTION);
132  printw("Goal x-y");
133  wmove(stdscr, GOAL_POS, X_VALUE);
134  PrintVector2D(goal_geom_.lin.p_.topRows(2));
135  printw(" [m]");
136 
137  wmove(stdscr, GOAL_ORI, X_KEY);
138  printw("keypad");
139  wmove(stdscr, GOAL_ORI, X_DESCRIPTION);
140  printw("Goal r-p-y");
141  wmove(stdscr, GOAL_ORI, X_VALUE);
143  printw(" [rad]");
144 
145  wmove(stdscr, ROBOT, X_KEY);
146  printw("r");
147  wmove(stdscr, ROBOT, X_DESCRIPTION);
148  printw("Robot");
149  wmove(stdscr, ROBOT, X_VALUE);
150  printw("%s\n", robot_names.at(static_cast<RobotModel::Robot>(robot_)).c_str());
151 
152  wmove(stdscr, GAIT, X_KEY);
153  printw("g");
154  wmove(stdscr, GAIT, X_DESCRIPTION);
155  printw("Gait");
156  wmove(stdscr, GAIT, X_VALUE);
157  printw("%s", std::to_string(gait_combo_).c_str());
158 
159  wmove(stdscr, OPTIMIZE_GAIT, X_KEY);
160  printw("y");
161  wmove(stdscr, OPTIMIZE_GAIT, X_DESCRIPTION);
162  printw("Optimize gait");
163  wmove(stdscr, OPTIMIZE_GAIT, X_VALUE);
164  optimize_phase_durations_? printw("On\n") : printw("off\n");
165 
166  wmove(stdscr, TERRAIN, X_KEY);
167  printw("t");
168  wmove(stdscr, TERRAIN, X_DESCRIPTION);
169  printw("Terrain");
170  wmove(stdscr, TERRAIN, X_VALUE);
171  printw("%s\n", terrain_names.at(static_cast<HeightMap::TerrainID>(terrain_)).c_str());
172 
173  wmove(stdscr, DURATION, X_KEY);
174  printw("+/-");
175  wmove(stdscr, DURATION, X_DESCRIPTION);
176  printw("Duration");
177  wmove(stdscr, DURATION, X_VALUE);
178  printw("%.2f [s]", total_duration_);
179 
180  wmove(stdscr, CLOSE, X_KEY);
181  printw("q");
182  wmove(stdscr, CLOSE, X_DESCRIPTION);
183  printw("Close user interface");
184  wmove(stdscr, CLOSE, X_VALUE);
185  printw("-");
186 }
187 
188 void
190 {
191  const static double d_lin = 0.1; // [m]
192  const static double d_ang = 0.25; // [rad]
193 
194  switch (c) {
195  case KEY_RIGHT:
196  goal_geom_.lin.p_.x() -= d_lin;
197  break;
198  case KEY_LEFT:
199  goal_geom_.lin.p_.x() += d_lin;
200  break;
201  case KEY_DOWN:
202  goal_geom_.lin.p_.y() += d_lin;
203  break;
204  case KEY_UP:
205  goal_geom_.lin.p_.y() -= d_lin;
206  break;
207  case KEY_PPAGE:
208  goal_geom_.lin.p_.z() += 0.5*d_lin;
209  break;
210  case KEY_NPAGE:
211  goal_geom_.lin.p_.z() -= 0.5*d_lin;
212  break;
213 
214  // desired goal orientations
215  case '4':
216  goal_geom_.ang.p_.x() -= d_ang; // roll-
217  break;
218  case '6':
219  goal_geom_.ang.p_.x() += d_ang; // roll+
220  break;
221  case '8':
222  goal_geom_.ang.p_.y() += d_ang; // pitch+
223  break;
224  case '2':
225  goal_geom_.ang.p_.y() -= d_ang; // pitch-
226  break;
227  case '1':
228  goal_geom_.ang.p_.z() += d_ang; // yaw+
229  break;
230  case '9':
231  goal_geom_.ang.p_.z() -= d_ang; // yaw-
232  break;
233 
234  // terrains
235  case 't':
237  break;
238 
239  case 'g':
241  break;
242 
243  case 'r':
245  break;
246 
247  // duration
248  case '+':
249  total_duration_ += 0.2;
250  break;
251  case '-':
252  total_duration_ -= 0.2;
253  break;
254  case '\'':
255  replay_speed_ += 0.1;
256  break;
257  case ';':
258  replay_speed_ -= 0.1;
259  break;
260  case 'y':
262  break;
263 
264 
265  case 'o':
266  optimize_ = true;
267  wmove(stdscr, Y_STATUS, 0);
268  printw("Optimizing motion\n\n");
269  break;
270  case 'v':
271  visualize_trajectory_ = true;
272  wmove(stdscr, Y_STATUS, 0);
273  printw("Visualizing current bag file\n\n");
274  break;
275  case 'i':
276  play_initialization_ = true;
277  wmove(stdscr, Y_STATUS, 0);
278  printw("Visualizing initialization (iteration 0)\n\n");
279  break;
280  case 'p':
281  plot_trajectory_ = true;
282  wmove(stdscr, Y_STATUS, 0);
283  printw("In rqt_bag: right-click on xpp/state_des -> View -> Plot.\n"
284  "Then expand the values you wish to plot on the right\n");
285  break;
286  case 'q':
287  printw("Closing user interface\n");
288  ros::shutdown(); break;
289  default:
290  break;
291  }
292 
293  PublishCommand();
294 }
295 
297 {
298  towr_ros::TowrCommand msg;
299  msg.goal_lin = xpp::Convert::ToRos(goal_geom_.lin);
300  msg.goal_ang = xpp::Convert::ToRos(goal_geom_.ang);
301  msg.total_duration = total_duration_;
302  msg.replay_trajectory = visualize_trajectory_;
303  msg.play_initialization = play_initialization_;
304  msg.replay_speed = replay_speed_;
305  msg.optimize = optimize_;
306  msg.terrain = terrain_;
307  msg.gait = gait_combo_;
308  msg.robot = robot_;
309  msg.optimize_phase_durations = optimize_phase_durations_;
310  msg.plot_trajectory = plot_trajectory_;
311 
313 
314  PrintScreen();
315 
316  optimize_ = false;
317  visualize_trajectory_ = false;
318  plot_trajectory_ = false;
319  play_initialization_ = false;
321 }
322 
323 int TowrUserInterface::AdvanceCircularBuffer(int& curr, int max) const
324 {
325  return curr==(max-1)? 0 : curr+1;
326 }
327 
328 void
329 TowrUserInterface::PrintVector(const Eigen::Vector3d& v) const
330 {
331  printw("%.2f %.2f %.2f", v.x(), v.y(), v.z());
332 }
333 
334 void
335 TowrUserInterface::PrintVector2D(const Eigen::Vector2d& v) const
336 {
337  printw("%.2f %.2f", v.x(), v.y());
338 }
339 
340 } /* namespace towr */
341 
342 
343 int main(int argc, char *argv[])
344 {
345  ros::init(argc, argv, "towr_user_iterface");
346 
347  initscr();
348  cbreak(); // disables buffering of types characters
349  noecho(); // suppresses automatic output of typed characters
350  keypad(stdscr, TRUE); // to capture special keypad characters
351 
352  towr::TowrUserInterface keyboard_user_interface;
353 
354  while (ros::ok())
355  {
356  int c = getch(); // call your non-blocking input function
357  keyboard_user_interface.CallbackKey(c);
358  refresh();
359  }
360 
361  endwin();
362 
363  return 1;
364 }
365 
static constexpr int Y_STATUS
static xpp_msgs::StateLin3d ToRos(const StateLin3d &xpp)
int AdvanceCircularBuffer(int &curr, int max) const
void publish(const boost::shared_ptr< M > &message) const
static const std::map< HeightMap::TerrainID, std::string > terrain_names
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
::ros::Publisher user_command_pub_
the output message to TOWR.
Translates user input into the ROS message TowrCommand.msg.
void PrintVector2D(const Eigen::Vector2d &v) const
xpp::State3dEuler goal_geom_
static constexpr int X_VALUE
ROSCPP_DECL bool ok()
int main(int argc, char *argv[])
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static constexpr int X_DESCRIPTION
TowrUserInterface()
Constructs default object to interact with framework.
void PrintVector(const Eigen::Vector3d &v) const
static const std::string user_command("/towr/user_command")
ROSCPP_DECL void shutdown()
static const std::map< RobotModel::Robot, std::string > robot_names
static constexpr int X_KEY


towr_ros
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 2 2021 02:14:21