example_teleop_node.cpp
Go to the documentation of this file.
1 #include <string>
2 
6 #include <radial_menu_msgs/State.h>
7 #include <ros/console.h>
8 #include <ros/init.h>
9 #include <ros/node_handle.h>
10 #include <sensor_msgs/Joy.h>
11 
13 std::string mode = "None";
14 bool paused = true;
15 
16 void onSynchronized(const sensor_msgs::JoyConstPtr &joy,
17  const radial_menu_msgs::StateConstPtr &state) {
18  namespace rmm = radial_menu_msgs;
19 
20  if (!model.setState(*state)) {
21  ROS_ERROR("onSynchronized(): Cannot set state to the model");
22  return;
23  }
24 
25  // parse the menu state
26  std::string new_mode;
27  bool new_paused;
28  if (model.isEnabled()) {
29  // if the menu is enabled (i.e. the joy input is owned by the menu),
30  // keep the current teleop mode and pause it
31  new_mode = mode;
32  new_paused = true;
33  } else {
34  // if the menu is disabled (i.e. the joy input is not owned by the menu),
35  // switch the teleop mode based on the menu item selected
36  if (model.isSelected("Teleop Mode.Base.Pose")) {
37  new_mode = "Base Pose";
38  } else if (model.isSelected("Teleop Mode.Base.Twist")) {
39  new_mode = "Base Twist";
40  } else if (model.isSelected("Teleop Mode.Arm.FK.Pose")) {
41  new_mode = "Arm FK Pose";
42  } else if (model.isSelected("Teleop Mode.Arm.FK.Twist")) {
43  new_mode = "Arm FK Twist";
44  } else if (model.isSelected("Teleop Mode.Arm.IK.Pose")) {
45  new_mode = "Arm IK Pose";
46  } else if (model.isSelected("Teleop Mode.Arm.IK.Twist")) {
47  new_mode = "Arm IK Twist";
48  } else if (model.isSelected("Teleop Mode.Arm.Hand")) {
49  new_mode = "Arm Hand";
50  } else {
51  new_mode = "None";
52  }
53  new_paused = false;
54  }
55 
56  // print the new mode on mode changed
57  if (new_mode != mode || new_paused != paused) {
58  mode = new_mode;
59  paused = new_paused;
60  ROS_INFO_STREAM("Teleop mode: " << mode << " (" << (paused ? "paused" : "enabled") << ")");
61  }
62 
63  // do something
64  // doTeleop(mode, paused, *joy);
65 }
66 
67 int main(int argc, char *argv[]) {
68  ros::init(argc, argv, "example_integration");
69  ros::NodeHandle nh;
70 
71  // init the menu tree model
72  if (!model.setDescriptionFromParam(nh.resolveName("teleop_menu_description"))) {
73  ROS_ERROR_STREAM("Cannot set menu description from the param '"
74  << nh.resolveName("teleop_menu_description"));
75  return 1;
76  }
77 
79  message_filters::Subscriber< radial_menu_msgs::State > menu_sub(nh, "teleop_menu_state", 1);
81  joy_sub, menu_sub, 10);
83 
84  ros::spin();
85 
86  return 0;
87 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool paused
void onSynchronized(const sensor_msgs::JoyConstPtr &joy, const radial_menu_msgs::StateConstPtr &state)
bool setDescriptionFromParam(const std::string &param_name)
int main(int argc, char *argv[])
bool setState(const radial_menu_msgs::State &new_state)
radial_menu_model::Model model
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void spin()
std::string mode
#define ROS_INFO_STREAM(args)
bool isSelected(const ItemConstPtr &item) const
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)


radial_menu_example
Author(s):
autogenerated on Mon Feb 28 2022 23:22:11