model.hpp
Go to the documentation of this file.
1 #ifndef RADIAL_MENU_MODEL_MODEL_HPP
2 #define RADIAL_MENU_MODEL_MODEL_HPP
3 
4 #include <algorithm>
5 #include <cstdint>
6 #include <memory>
7 #include <string>
8 #include <vector>
9 
11 #include <radial_menu_msgs/State.h>
12 #include <ros/console.h>
13 #include <ros/exception.h>
14 #include <ros/param.h>
15 #include <ros/time.h>
16 
17 namespace radial_menu_model {
18 
19 class Model;
20 typedef std::shared_ptr< Model > ModelPtr;
21 typedef std::shared_ptr< const Model > ModelConstPtr;
22 
23 class Model {
24 public:
25  Model() {
27  resetState();
28  }
29 
30  virtual ~Model() {}
31 
32  // **************
33  // Current status
34  // **************
35 
36  ItemConstPtr root() const { return current_level_->root(); }
37 
39 
41  return (state_.pointed_id >= 0 && state_.pointed_id < items_.size()) ? items_[state_.pointed_id]
42  : ItemConstPtr();
43  }
44 
45  bool isPointed(const ItemConstPtr &item) const { return item && item == pointed(); }
46 
47  bool isPointed(const std::string &path, const char separator = '.') const {
48  const ItemConstPtr p(pointed());
49  return p ? (path == p->path(separator)) : false;
50  }
51 
52  std::vector< ItemConstPtr > selected() const {
53  std::vector< ItemConstPtr > items;
54  for (const std::int32_t iid : state_.selected_ids) {
55  if (iid >= 0 && iid < items_.size()) {
56  items.push_back(items_[iid]);
57  }
58  }
59  return items;
60  }
61 
62  bool isSelected(const ItemConstPtr &item) const {
63  if (!item) {
64  return false;
65  }
66  for (const std::int32_t iid : state_.selected_ids) {
67  if (iid >= 0 && iid < items_.size() && item == items_[iid]) {
68  return true;
69  }
70  }
71  return false;
72  }
73 
74  bool isSelected(const std::string &path, const char separator = '.') const {
75  for (const std::int32_t iid : state_.selected_ids) {
76  if (iid >= 0 && iid < items_.size() && path == items_[iid]->path(separator)) {
77  return true;
78  }
79  }
80  return false;
81  }
82 
83  ItemConstPtr sibilingByAngle(double angle) const {
84  // make the given angle positive, or the returned value may be going to be negative
85  while (angle < 0.) {
86  angle += 2. * M_PI;
87  }
88  const int n_sibilings(current_level_->numSibilings());
89  const double span_angle(2. * M_PI / n_sibilings);
90  const int sid(static_cast< int >(std::round(angle / span_angle)) % n_sibilings);
91  return current_level_->sibiling(sid);
92  }
93 
94  // ***********
95  // Description
96  // ***********
97 
98  // set new model tree description. also rests the state
99  bool setDescription(const std::string &desc) {
100  // populate items in the item tree
101  const std::vector< ItemConstPtr > new_items(Item::itemsFromDescription(desc));
102  if (new_items.empty()) {
103  ROS_ERROR("Model::setDescription(): No items");
104  return false;
105  }
106 
107  // set the initial level of the model
108  const ItemConstPtr new_current_level(new_items.front()->childLevel());
109  if (!new_current_level) {
110  ROS_ERROR("Model::setDescription(): No children of the root item");
111  return false;
112  }
113 
114  // set new description (also reset the state)
115  items_ = new_items;
116  current_level_ = new_current_level;
117  state_ = defaultState();
118  return true;
119  }
120 
121  // set new description obtained from a ROS param server
122  bool setDescriptionFromParam(const std::string &param_name) {
123  std::string desc;
124  if (ros::param::get(param_name, desc)) {
125  return setDescription(desc);
126  } else {
127  ROS_ERROR_STREAM("Model::setDescriptionFromParam(): Cannot get the param '" << param_name
128  << "'");
129  return false;
130  }
131  }
132 
134 
135  static std::string defaultDescription() {
136  // this is useless as an actual menu, but keeps items_ & current_level_ valid
137  return "<item name=\"Menu\">\n"
138  " <item name=\"Item\" />\n"
139  "</item>";
140  }
141 
142  // *****
143  // State
144  // *****
145 
146  radial_menu_msgs::StatePtr exportState(const ros::Time stamp = ros::Time::now()) const {
147  radial_menu_msgs::StatePtr state(new radial_menu_msgs::State(state_));
148  state->header.stamp = stamp;
149  return state;
150  }
151 
152  // set new state. also update the current level
153  bool setState(const radial_menu_msgs::State &new_state) {
154  state_ = new_state;
155 
156  // update the current level by moving to the deepest level of selected items or its children
157  current_level_ = items_.front()->childLevel();
158  for (const std::int32_t iid : state_.selected_ids) {
159  if (iid >= 0 && iid < items_.size()) {
160  const ItemConstPtr item(items_[iid]);
161  ItemConstPtr level(item->childLevel());
162  if (!level) {
163  level = item->sibilingLevel();
164  }
165  if (level->depth() > current_level_->depth()) {
166  current_level_ = level;
167  }
168  }
169  }
170 
171  return true;
172  }
173 
174  bool resetState() { return setState(defaultState()); }
175 
176  static radial_menu_msgs::State defaultState() {
177  radial_menu_msgs::State state;
178  state.is_enabled = false;
179  state.pointed_id = -1;
180  return state;
181  }
182 
183  // ********
184  // Enabling
185  // ********
186 
187  bool isEnabled() const { return state_.is_enabled; }
188 
189  void setEnabled(const bool is_enabled) { state_.is_enabled = is_enabled; }
190 
191  // *********************
192  // Pointing / Unpointing
193  // *********************
194 
195  // can point if the given item is in the current level and not pointed
196  bool canPoint(const ItemConstPtr &item) const {
197  return item && item->sibilingLevel() == current_level_ && !isPointed(item);
198  }
199 
200  // move the point to the given item
201  void point(const ItemConstPtr &item) {
202  if (canPoint(item)) {
203  state_.pointed_id = item->itemId();
204  return;
205  }
206  throw ros::Exception("Model::point()");
207  }
208 
209  // can unpoint if the given item is in the current level and pointed
210  bool canUnpoint(const ItemConstPtr &item) const {
211  return item && item->sibilingLevel() == current_level_ && isPointed(item);
212  }
213 
214  // just unpoint the given item
215  void unpoint(const ItemConstPtr &item) {
216  if (canUnpoint(item)) {
217  state_.pointed_id = -1;
218  return;
219  }
220  throw ros::Exception("Model::unpoint()");
221  }
222 
223  // ****************************
224  // Leaf selection / deselection
225  // ****************************
226 
227  // can select if the given item is in the current level, has no child level, and is not selected
228  bool canSelect(const ItemConstPtr &item) const {
229  return item && item->sibilingLevel() == current_level_ && !item->childLevel() &&
230  !isSelected(item);
231  }
232 
233  // deselect all sibilings and select the given item.
234  // deselect will be skipped if allow_multi_selection is true.
235  void select(const ItemConstPtr &item, const bool allow_multi_selection) {
236  if (canSelect(item)) {
237  if (!allow_multi_selection) {
238  for (const ItemConstPtr &sibiling : current_level_->sibilings()) {
239  forceDeselect(sibiling);
240  }
241  }
242  forceSelect(item);
243  return;
244  }
245  throw ros::Exception("Model::select()");
246  }
247 
248  // can deselect if the given item is in the current level, has no child level, and is selected
249  bool canDeselect(const ItemConstPtr &item) const {
250  return item && item->sibilingLevel() == current_level_ && !item->childLevel() &&
251  isSelected(item);
252  }
253 
254  // just deselect the given item
255  void deselect(const ItemConstPtr &item) {
256  if (canDeselect(item)) {
257  forceDeselect(item);
258  return;
259  }
260  throw ros::Exception("Model::deselect()");
261  }
262 
263  // **********************
264  // Descending / Ascending
265  // **********************
266 
267  // can descend if the given item is in the current level and has a child level
268  bool canDescend(const ItemConstPtr &item) const {
269  return item && item->sibilingLevel() == current_level_ && item->childLevel();
270  }
271 
272  // unpoint and deselect all sibilings, select the given item
273  // and move to the child level of the given item.
274  // deselect will be skipped if allow_multi_selection is true.
275  void descend(const ItemConstPtr &item, const bool allow_multi_selection) {
276  if (canDescend(item)) {
277  state_.pointed_id = -1;
278  if (!allow_multi_selection) {
279  for (const ItemConstPtr &sibiling : current_level_->sibilings()) {
280  forceDeselect(sibiling);
281  }
282  }
283  forceSelect(item);
284  current_level_ = item->childLevel();
285  return;
286  }
287  throw ros::Exception("Model::descend()");
288  }
289 
290  // can ascend if the current level is not the first
291  bool canAscend() const { return current_level_->depth() >= 2; }
292 
293  // unpoint and deselect all sibilings, deselect and move to the parent level
294  void ascend() {
295  if (canAscend()) {
296  state_.pointed_id = -1;
297  for (const ItemConstPtr &sibiling : current_level_->sibilings()) {
298  forceDeselect(sibiling);
299  }
300  forceDeselect(current_level_->parent());
301  current_level_ = current_level_->parentLevel();
302  return;
303  }
304  throw ros::Exception("Model::ascend()");
305  }
306 
307  // *****
308  // Debug
309  // *****
310 
311  std::string toString() const {
312  struct Internal {
313  static std::string toString(const Model *const model, const ItemConstPtr &item,
314  const int n_indent = 0) {
315  std::string str(n_indent, ' ');
316  if (item) {
317  if (item->depth() > 0) {
318  str += itemStateStr(model, item) + " ";
319  }
320  str += item->name() + " " + itemIdStr(item) + "\n";
321  for (const ItemConstPtr &child : item->children()) {
322  str += toString(model, child, n_indent + 2);
323  }
324  } else {
325  str += " -\n";
326  }
327  return str;
328  }
329 
330  static std::string itemStateStr(const Model *const model, const ItemConstPtr &item) {
331  std::ostringstream str;
332  str << "[" << (model->isPointed(item) ? "P" : " ") << (model->isSelected(item) ? "S" : " ")
333  << (item == model->currentLevel() ? "C" : " ") << "]";
334  return str.str();
335  }
336 
337  static std::string itemIdStr(const ItemConstPtr &item) {
338  std::ostringstream str;
339  str << "(i" << item->itemId() << "-d" << item->depth() << ")";
340  return str.str();
341  }
342  };
343 
344  return Internal::toString(this, items_.front());
345  }
346 
347 protected:
348  // ************
349  // Internal use
350  // ************
351 
352  void forceSelect(const ItemConstPtr &item) {
353  if (item) {
354  std::vector< std::int32_t > &ids(state_.selected_ids);
355  if (std::find(ids.begin(), ids.end(), item->itemId()) == ids.end()) {
356  ids.push_back(item->itemId());
357  }
358  }
359  }
360 
361  void forceDeselect(const ItemConstPtr &item) {
362  if (item) {
363  std::vector< std::int32_t > &ids(state_.selected_ids);
364  ids.erase(std::remove(ids.begin(), ids.end(), item->itemId()), ids.end());
365  }
366  }
367 
368 protected:
369  std::vector< ItemConstPtr > items_;
371  radial_menu_msgs::State state_;
372 };
373 } // namespace radial_menu_model
374 
375 #endif
std::shared_ptr< const Item > ItemConstPtr
Definition: item.hpp:18
static radial_menu_msgs::State defaultState()
Definition: model.hpp:176
bool isEnabled() const
Definition: model.hpp:187
bool canAscend() const
Definition: model.hpp:291
ItemConstPtr sibilingByAngle(double angle) const
Definition: model.hpp:83
std::vector< ItemConstPtr > items_
Definition: model.hpp:369
void forceDeselect(const ItemConstPtr &item)
Definition: model.hpp:361
ItemConstPtr currentLevel() const
Definition: model.hpp:38
radial_menu_msgs::State state_
Definition: model.hpp:371
bool canUnpoint(const ItemConstPtr &item) const
Definition: model.hpp:210
void forceSelect(const ItemConstPtr &item)
Definition: model.hpp:352
bool setDescriptionFromParam(const std::string &param_name)
Definition: model.hpp:122
std::shared_ptr< const Model > ModelConstPtr
Definition: model.hpp:21
bool canDescend(const ItemConstPtr &item) const
Definition: model.hpp:268
static std::string defaultDescription()
Definition: model.hpp:135
static std::vector< ItemConstPtr > itemsFromDescription(const std::string &desc)
Definition: item.hpp:128
bool isPointed(const std::string &path, const char separator='.') const
Definition: model.hpp:47
radial_menu_msgs::StatePtr exportState(const ros::Time stamp=ros::Time::now()) const
Definition: model.hpp:146
bool setState(const radial_menu_msgs::State &new_state)
Definition: model.hpp:153
ROSCPP_DECL bool get(const std::string &key, std::string &s)
ItemConstPtr pointed() const
Definition: model.hpp:40
void select(const ItemConstPtr &item, const bool allow_multi_selection)
Definition: model.hpp:235
ItemConstPtr root() const
Definition: model.hpp:36
std::shared_ptr< Model > ModelPtr
Definition: model.hpp:19
std::string toString() const
Definition: model.hpp:311
void unpoint(const ItemConstPtr &item)
Definition: model.hpp:215
bool canPoint(const ItemConstPtr &item) const
Definition: model.hpp:196
bool setDescription(const std::string &desc)
Definition: model.hpp:99
void deselect(const ItemConstPtr &item)
Definition: model.hpp:255
ItemConstPtr current_level_
Definition: model.hpp:370
bool canSelect(const ItemConstPtr &item) const
Definition: model.hpp:228
void descend(const ItemConstPtr &item, const bool allow_multi_selection)
Definition: model.hpp:275
void point(const ItemConstPtr &item)
Definition: model.hpp:201
bool canDeselect(const ItemConstPtr &item) const
Definition: model.hpp:249
bool isPointed(const ItemConstPtr &item) const
Definition: model.hpp:45
static Time now()
bool isSelected(const ItemConstPtr &item) const
Definition: model.hpp:62
bool isSelected(const std::string &path, const char separator='.') const
Definition: model.hpp:74
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
void setEnabled(const bool is_enabled)
Definition: model.hpp:189
std::vector< ItemConstPtr > selected() const
Definition: model.hpp:52


radial_menu_model
Author(s):
autogenerated on Mon Feb 28 2022 23:22:00