36 #include <towr_ros/TowrCommand.h> 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");
89 wmove(stdscr,
HEADING, X_DESCRIPTION);
90 printw(
"Description");
91 wmove(stdscr,
HEADING, X_VALUE);
96 wmove(stdscr,
OPTIMIZE, X_DESCRIPTION);
97 printw(
"Optimize motion");
104 printw(
"visualize motion in rviz");
111 printw(
"play initialization");
115 wmove(stdscr,
PLOT, X_KEY);
117 wmove(stdscr,
PLOT, X_DESCRIPTION);
118 printw(
"Plot values (rqt_bag)");
119 wmove(stdscr,
PLOT, X_VALUE);
125 printw(
"Replay speed");
131 wmove(stdscr,
GOAL_POS, X_DESCRIPTION);
139 wmove(stdscr,
GOAL_ORI, X_DESCRIPTION);
140 printw(
"Goal r-p-y");
145 wmove(stdscr,
ROBOT, X_KEY);
147 wmove(stdscr,
ROBOT, X_DESCRIPTION);
149 wmove(stdscr,
ROBOT, X_VALUE);
152 wmove(stdscr,
GAIT, X_KEY);
154 wmove(stdscr,
GAIT, X_DESCRIPTION);
156 wmove(stdscr,
GAIT, X_VALUE);
162 printw(
"Optimize gait");
168 wmove(stdscr,
TERRAIN, X_DESCRIPTION);
170 wmove(stdscr,
TERRAIN, X_VALUE);
175 wmove(stdscr,
DURATION, X_DESCRIPTION);
180 wmove(stdscr,
CLOSE, X_KEY);
182 wmove(stdscr,
CLOSE, X_DESCRIPTION);
183 printw(
"Close user interface");
184 wmove(stdscr,
CLOSE, X_VALUE);
191 const static double d_lin = 0.1;
192 const static double d_ang = 0.25;
267 wmove(stdscr, Y_STATUS, 0);
268 printw(
"Optimizing motion\n\n");
272 wmove(stdscr, Y_STATUS, 0);
273 printw(
"Visualizing current bag file\n\n");
277 wmove(stdscr, Y_STATUS, 0);
278 printw(
"Visualizing initialization (iteration 0)\n\n");
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");
287 printw(
"Closing user interface\n");
298 towr_ros::TowrCommand msg;
325 return curr==(max-1)? 0 : curr+1;
331 printw(
"%.2f %.2f %.2f", v.x(), v.y(), v.z());
337 printw(
"%.2f %.2f", v.x(), v.y());
343 int main(
int argc,
char *argv[])
345 ros::init(argc, argv,
"towr_user_iterface");
350 keypad(stdscr, TRUE);
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
bool optimize_phase_durations_
int main(int argc, char *argv[])
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static constexpr int X_DESCRIPTION
bool publish_optimized_trajectory_
bool play_initialization_
bool visualize_trajectory_
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