action_editor.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /*
18  * action_editor.h
19  *
20  * Created on: 2016. 12. 16.
21  * Author: Jay Song
22  */
23 
24 #ifndef THORMANG3_ACTION_EDITOR_ACTION_EDITOR_H_
25 #define THORMANG3_ACTION_EDITOR_ACTION_EDITOR_H_
26 
27 #include <stdio.h>
28 #include <stdlib.h>
29 #include <string>
30 #include <unistd.h>
31 #include <termios.h>
32 #include <term.h>
33 #include <fcntl.h>
34 #include <ncurses.h>
35 #include <pthread.h>
36 #include <sys/wait.h>
37 #include <ros/ros.h>
38 
40 
42 
43 #define ROBOT_NAME "THORMANG3"
44 
45 namespace thormang3
46 {
47 
49 {
50 public:
52  {
56  };
58  {
59  UpperBody = 1,
60  LowerBody = 2,
61  AllBody = 3
62  };
63 
64  ActionEditor();
65  ~ActionEditor();
66 
67  int _getch();
68  int kbhit();
69 
70  // Move cursor
71  void goToCursor(int col, int row);
72  void moveUpCursor();
73  void moveDownCursor();
74  void moveLeftCursor();
75  void moveRightCursor();
76 
77  bool initializeActionEditor(std::string robot_file_path, std::string init_file_path, std::string offset_file_path);
78 
79  // Disp & Drawing
80  void drawIntro();
81  void drawEnding();
82  void drawPage();
83  void drawStep(int index);
84  void drawName();
85  void drawStepLine(bool erase);
86  void readStep();
87  void clearCmd();
88  void printCmd(const char *message);
89  bool askSave();
90 
91 
92  // Edit value
93  void setValueUpDown(int offset);
94  void setValue(int value);
95  int getValue();
96  void toggleTorque();
97  void storeValueToCache();
98  void setValueFromCache();
99  void clearCache();
100 
101  // Command process
102  void beginCommandMode();
103  void endCommandMode();
104  void helpCmd();
105  void nextCmd();
106  void prevCmd();
107  void pageCmd(int index);
108  void timeCmd();
109  void speedCmd();
110  void playCmd();
111  void playCmd(int mp3_index);
112  void playCmd(const char* file_path);
113  void listCmd();
114  void turnOnOffCmd(bool on, int num_param, int *list);
115  void mirrorStepCmd(int index, int mirror_type, int target_type);
116  void writeStepCmd(int index);
117  void deleteStepCmd(int index);
118  void insertStepCmd(int index);
119  void moveStepCmd(int src, int dst);
120  void copyCmd(int index);
121  void newCmd();
122  void goCmd(int index);
123  void saveCmd();
124  void nameCmd();
125 
128 
129 private:
130  void setSTDin();
131  void resetSTDin();
132 
133  int convert4095ToPositionValue(int id, int w4095);
134  int convertPositionValueTo4095(int id, int PositionValue);
135  int convert4095ToMirror(int id, int w4095);
136 
137  bool loadMp3Path(int mp3_index, std::string &path);
138  bool loadMirrorJoint();
139 
140  struct termios oldterm, new_term;
143 
146 
149 
150  std::map<int, std::string> joint_id_to_name_;
151  std::map<int, int> joint_id_to_row_index_;
152  std::map<int, int> joint_row_index_to_id_;
153  std::map<std::string, int> joint_name_to_id_;
154 
155  std::map<int, int> upper_body_mirror_joints_rl_;
156  std::map<int, int> upper_body_mirror_joints_lr_;
157  std::map<int, int> lower_body_mirror_joints_rl_;
158  std::map<int, int> lower_body_mirror_joints_lr_;
159 
162 
163  std::map<std::string, dynamixel::GroupSyncWrite *> port_to_sync_write_go_cmd_;
164 
166  bool edited_;
168 
169  int curr_col_ ;
171  int old_col_;
172  int old_row_;
173 
175 
176  int cmd_col_;
191 
195 
198  int cmd_row_;
199 
210 };
211 
212 }
213 
214 #endif /* THORMANG3_ACTION_EDITOR_ACTION_EDITOR_H_ */
bool loadMp3Path(int mp3_index, std::string &path)
void deleteStepCmd(int index)
int convert4095ToMirror(int id, int w4095)
int convert4095ToPositionValue(int id, int w4095)
bool initializeActionEditor(std::string robot_file_path, std::string init_file_path, std::string offset_file_path)
ros::Publisher play_sound_pub_
void writeStepCmd(int index)
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_go_cmd_
void drawStep(int index)
void setValueUpDown(int offset)
std::string default_editor_script_path_
std::map< int, int > joint_id_to_row_index_
std::map< int, int > lower_body_mirror_joints_rl_
int convertPositionValueTo4095(int id, int PositionValue)
void goToCursor(int col, int row)
std::map< int, int > upper_body_mirror_joints_lr_
void printCmd(const char *message)
void insertStepCmd(int index)
void moveStepCmd(int src, int dst)
action_file_define::Step step_
struct termios oldterm new_term
void mirrorStepCmd(int index, int mirror_type, int target_type)
void turnOnOffCmd(bool on, int num_param, int *list)
robotis_framework::Robot * robot_
std::string mirror_joint_file_path_
void drawStepLine(bool erase)
std::map< int, int > lower_body_mirror_joints_lr_
std::map< std::string, int > joint_name_to_id_
void setValue(int value)
std::map< int, std::string > joint_id_to_name_
robotis_framework::RobotisController * ctrl_
ros::Publisher enable_ctrl_module_pub_
std::map< int, int > joint_row_index_to_id_
std::map< int, int > upper_body_mirror_joints_rl_
action_file_define::Page page_


thormang3_action_editor
Author(s): Kayman , SCH , Jay Song
autogenerated on Mon Jun 10 2019 15:37:46