towr_user_interface.cc
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without
00005 modification, are permitted provided that the following conditions are met:
00006 
00007 * Redistributions of source code must retain the above copyright notice, this
00008   list of conditions and the following disclaimer.
00009 
00010 * Redistributions in binary form must reproduce the above copyright notice,
00011   this list of conditions and the following disclaimer in the documentation
00012   and/or other materials provided with the distribution.
00013 
00014 * Neither the name of the copyright holder nor the names of its
00015   contributors may be used to endorse or promote products derived from
00016   this software without specific prior written permission.
00017 
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 ******************************************************************************/
00029 
00030 #include <towr_ros/towr_user_interface.h>
00031 
00032 #include <ncurses.h>
00033 
00034 #include <xpp_states/convert.h>
00035 
00036 #include <towr_ros/TowrCommand.h>
00037 #include <towr_ros/topic_names.h>
00038 #include <towr/terrain/height_map.h>
00039 #include <towr/initialization/gait_generator.h>
00040 #include <towr/models/robot_model.h>
00041 
00042 
00043 namespace towr {
00044 
00045 
00046 enum YCursorRows {HEADING=6, OPTIMIZE=8, VISUALIZE, INITIALIZATION, PLOT,
00047                   REPLAY_SPEED, GOAL_POS, GOAL_ORI, ROBOT,
00048                   GAIT, OPTIMIZE_GAIT, TERRAIN, DURATION, CLOSE, END};
00049 static constexpr int Y_STATUS      = END+1;
00050 static constexpr int X_KEY         = 1;
00051 static constexpr int X_DESCRIPTION = 10;
00052 static constexpr int X_VALUE       = 35;
00053 
00054 
00055 TowrUserInterface::TowrUserInterface ()
00056 {
00057   printw(" ******************************************************************************\n");
00058   printw("                          TOWR user interface (v1.4) \n");
00059   printw("                            \u00a9 Alexander W. Winkler \n");
00060   printw("                        https://github.com/ethz-adrl/towr\n");
00061   printw(" ******************************************************************************\n\n");
00062 
00063   ::ros::NodeHandle n;
00064   user_command_pub_ = n.advertise<towr_ros::TowrCommand>(towr_msgs::user_command, 1);
00065 
00066   goal_geom_.lin.p_.setZero();
00067   goal_geom_.lin.p_ << 2.1, 0.0, 0.0;
00068   goal_geom_.ang.p_ << 0.0, 0.0, 0.0; // roll, pitch, yaw angle applied Z->Y'->X''
00069 
00070   robot_      = RobotModel::Monoped;
00071   terrain_    = HeightMap::FlatID;
00072   gait_combo_ = GaitGenerator::C0;
00073   total_duration_ = 2.4;
00074   visualize_trajectory_ = false;
00075   plot_trajectory_ = false;
00076   replay_speed_ = 1.0; // realtime
00077   optimize_ = false;
00078   publish_optimized_trajectory_ = false;
00079   optimize_phase_durations_ = false;
00080 
00081   PrintScreen();
00082 }
00083 
00084 void
00085 TowrUserInterface::PrintScreen() const
00086 {
00087   wmove(stdscr, HEADING, X_KEY);
00088   printw("Key");
00089   wmove(stdscr, HEADING, X_DESCRIPTION);
00090   printw("Description");
00091   wmove(stdscr, HEADING, X_VALUE);
00092   printw("Info");
00093 
00094   wmove(stdscr, OPTIMIZE, X_KEY);
00095   printw("o");
00096   wmove(stdscr, OPTIMIZE, X_DESCRIPTION);
00097   printw("Optimize motion");
00098   wmove(stdscr, OPTIMIZE, X_VALUE);
00099   printw("-");
00100 
00101   wmove(stdscr, VISUALIZE, X_KEY);
00102   printw("v");
00103   wmove(stdscr, VISUALIZE, X_DESCRIPTION);
00104   printw("visualize motion in rviz");
00105   wmove(stdscr, VISUALIZE, X_VALUE);
00106   printw("-");
00107 
00108   wmove(stdscr, INITIALIZATION, X_KEY);
00109   printw("i");
00110   wmove(stdscr, INITIALIZATION, X_DESCRIPTION);
00111   printw("play initialization");
00112   wmove(stdscr, INITIALIZATION, X_VALUE);
00113   printw("-");
00114 
00115   wmove(stdscr, PLOT, X_KEY);
00116   printw("p");
00117   wmove(stdscr, PLOT, X_DESCRIPTION);
00118   printw("Plot values (rqt_bag)");
00119   wmove(stdscr, PLOT, X_VALUE);
00120   printw("-");
00121 
00122   wmove(stdscr, REPLAY_SPEED, X_KEY);
00123   printw(";/'");
00124   wmove(stdscr, REPLAY_SPEED, X_DESCRIPTION);
00125   printw("Replay speed");
00126   wmove(stdscr, REPLAY_SPEED, X_VALUE);
00127   printw("%.2f", replay_speed_);
00128 
00129   wmove(stdscr, GOAL_POS, X_KEY);
00130   printw("arrows");
00131   wmove(stdscr, GOAL_POS, X_DESCRIPTION);
00132   printw("Goal x-y");
00133   wmove(stdscr, GOAL_POS, X_VALUE);
00134   PrintVector2D(goal_geom_.lin.p_.topRows(2));
00135   printw(" [m]");
00136 
00137   wmove(stdscr, GOAL_ORI, X_KEY);
00138   printw("keypad");
00139   wmove(stdscr, GOAL_ORI, X_DESCRIPTION);
00140   printw("Goal r-p-y");
00141   wmove(stdscr, GOAL_ORI, X_VALUE);
00142   PrintVector(goal_geom_.ang.p_);
00143   printw(" [rad]");
00144 
00145   wmove(stdscr, ROBOT, X_KEY);
00146   printw("r");
00147   wmove(stdscr, ROBOT, X_DESCRIPTION);
00148   printw("Robot");
00149   wmove(stdscr, ROBOT, X_VALUE);
00150   printw("%s\n", robot_names.at(static_cast<RobotModel::Robot>(robot_)).c_str());
00151 
00152   wmove(stdscr, GAIT, X_KEY);
00153   printw("g");
00154   wmove(stdscr, GAIT, X_DESCRIPTION);
00155   printw("Gait");
00156   wmove(stdscr, GAIT, X_VALUE);
00157   printw("%s", std::to_string(gait_combo_).c_str());
00158 
00159   wmove(stdscr, OPTIMIZE_GAIT, X_KEY);
00160   printw("y");
00161   wmove(stdscr, OPTIMIZE_GAIT, X_DESCRIPTION);
00162   printw("Optimize gait");
00163   wmove(stdscr, OPTIMIZE_GAIT, X_VALUE);
00164   optimize_phase_durations_? printw("On\n") : printw("off\n");
00165 
00166   wmove(stdscr, TERRAIN, X_KEY);
00167   printw("t");
00168   wmove(stdscr, TERRAIN, X_DESCRIPTION);
00169   printw("Terrain");
00170   wmove(stdscr, TERRAIN, X_VALUE);
00171   printw("%s\n", terrain_names.at(static_cast<HeightMap::TerrainID>(terrain_)).c_str());
00172 
00173   wmove(stdscr, DURATION, X_KEY);
00174   printw("+/-");
00175   wmove(stdscr, DURATION, X_DESCRIPTION);
00176   printw("Duration");
00177   wmove(stdscr, DURATION, X_VALUE);
00178   printw("%.2f [s]", total_duration_);
00179 
00180   wmove(stdscr, CLOSE, X_KEY);
00181   printw("q");
00182   wmove(stdscr, CLOSE, X_DESCRIPTION);
00183   printw("Close user interface");
00184   wmove(stdscr, CLOSE, X_VALUE);
00185   printw("-");
00186 }
00187 
00188 void
00189 TowrUserInterface::CallbackKey (int c)
00190 {
00191   const static double d_lin = 0.1;  // [m]
00192   const static double d_ang = 0.25; // [rad]
00193 
00194   switch (c) {
00195     case KEY_RIGHT:
00196       goal_geom_.lin.p_.x() -= d_lin;
00197       break;
00198     case KEY_LEFT:
00199       goal_geom_.lin.p_.x() += d_lin;
00200       break;
00201     case KEY_DOWN:
00202       goal_geom_.lin.p_.y() += d_lin;
00203       break;
00204     case KEY_UP:
00205       goal_geom_.lin.p_.y() -= d_lin;
00206       break;
00207     case KEY_PPAGE:
00208       goal_geom_.lin.p_.z() += 0.5*d_lin;
00209       break;
00210     case KEY_NPAGE:
00211       goal_geom_.lin.p_.z() -= 0.5*d_lin;
00212       break;
00213 
00214     // desired goal orientations
00215     case '4':
00216       goal_geom_.ang.p_.x() -= d_ang; // roll-
00217       break;
00218     case '6':
00219       goal_geom_.ang.p_.x() += d_ang; // roll+
00220       break;
00221     case '8':
00222       goal_geom_.ang.p_.y() += d_ang; // pitch+
00223       break;
00224     case '2':
00225       goal_geom_.ang.p_.y() -= d_ang; // pitch-
00226       break;
00227     case '1':
00228       goal_geom_.ang.p_.z() += d_ang; // yaw+
00229       break;
00230     case '9':
00231       goal_geom_.ang.p_.z() -= d_ang; // yaw-
00232       break;
00233 
00234     // terrains
00235     case 't':
00236       terrain_ = AdvanceCircularBuffer(terrain_, HeightMap::TERRAIN_COUNT);
00237       break;
00238 
00239     case 'g':
00240       gait_combo_ = AdvanceCircularBuffer(gait_combo_, GaitGenerator::COMBO_COUNT);
00241       break;
00242 
00243     case 'r':
00244       robot_ = AdvanceCircularBuffer(robot_, RobotModel::ROBOT_COUNT);
00245       break;
00246 
00247     // duration
00248     case '+':
00249       total_duration_ += 0.2;
00250     break;
00251     case '-':
00252       total_duration_ -= 0.2;
00253     break;
00254     case '\'':
00255       replay_speed_ += 0.1;
00256     break;
00257     case ';':
00258       replay_speed_ -= 0.1;
00259     break;
00260     case 'y':
00261       optimize_phase_durations_ = !optimize_phase_durations_;
00262       break;
00263 
00264 
00265     case 'o':
00266       optimize_ = true;
00267       wmove(stdscr, Y_STATUS, 0);
00268       printw("Optimizing motion\n\n");
00269       break;
00270     case 'v':
00271       visualize_trajectory_ = true;
00272       wmove(stdscr, Y_STATUS, 0);
00273       printw("Visualizing current bag file\n\n");
00274       break;
00275     case 'i':
00276       play_initialization_ = true;
00277       wmove(stdscr, Y_STATUS, 0);
00278       printw("Visualizing initialization (iteration 0)\n\n");
00279       break;
00280     case 'p':
00281       plot_trajectory_ = true;
00282       wmove(stdscr, Y_STATUS, 0);
00283       printw("In rqt_bag: right-click on xpp/state_des -> View -> Plot.\n"
00284              "Then expand the values you wish to plot on the right\n");
00285       break;
00286     case 'q':
00287       printw("Closing user interface\n");
00288       ros::shutdown(); break;
00289     default:
00290       break;
00291   }
00292 
00293   PublishCommand();
00294 }
00295 
00296 void TowrUserInterface::PublishCommand()
00297 {
00298   towr_ros::TowrCommand msg;
00299   msg.goal_lin                 = xpp::Convert::ToRos(goal_geom_.lin);
00300   msg.goal_ang                 = xpp::Convert::ToRos(goal_geom_.ang);
00301   msg.total_duration           = total_duration_;
00302   msg.replay_trajectory        = visualize_trajectory_;
00303   msg.play_initialization      = play_initialization_;
00304   msg.replay_speed             = replay_speed_;
00305   msg.optimize                 = optimize_;
00306   msg.terrain                  = terrain_;
00307   msg.gait                     = gait_combo_;
00308   msg.robot                    = robot_;
00309   msg.optimize_phase_durations = optimize_phase_durations_;
00310   msg.plot_trajectory          = plot_trajectory_;
00311 
00312   user_command_pub_.publish(msg);
00313 
00314   PrintScreen();
00315 
00316   optimize_ = false;
00317   visualize_trajectory_ = false;
00318   plot_trajectory_ = false;
00319   play_initialization_ = false;
00320   publish_optimized_trajectory_ = false;
00321 }
00322 
00323 int TowrUserInterface::AdvanceCircularBuffer(int& curr, int max) const
00324 {
00325   return curr==(max-1)? 0 : curr+1;
00326 }
00327 
00328 void
00329 TowrUserInterface::PrintVector(const Eigen::Vector3d& v) const
00330 {
00331   printw("%.2f  %.2f  %.2f", v.x(), v.y(), v.z());
00332 }
00333 
00334 void
00335 TowrUserInterface::PrintVector2D(const Eigen::Vector2d& v) const
00336 {
00337   printw("%.2f  %.2f", v.x(), v.y());
00338 }
00339 
00340 } /* namespace towr */
00341 
00342 
00343 int main(int argc, char *argv[])
00344 {
00345   ros::init(argc, argv, "towr_user_iterface");
00346 
00347   initscr();
00348   cbreak();              // disables buffering of types characters
00349   noecho();              // suppresses automatic output of typed characters
00350   keypad(stdscr, TRUE);  // to capture special keypad characters
00351 
00352   towr::TowrUserInterface keyboard_user_interface;
00353 
00354   while (ros::ok())
00355   {
00356     int c = getch(); // call your non-blocking input function
00357     keyboard_user_interface.CallbackKey(c);
00358     refresh();
00359   }
00360 
00361   endwin();
00362 
00363   return 1;
00364 }
00365 


towr_ros
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 15 2019 02:42:39