6 #include <radial_menu_msgs/State.h> 10 #include <sensor_msgs/Joy.h> 17 const radial_menu_msgs::StateConstPtr &state) {
18 namespace rmm = radial_menu_msgs;
21 ROS_ERROR(
"onSynchronized(): Cannot set state to the model");
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";
57 if (new_mode !=
mode || new_paused !=
paused) {
67 int main(
int argc,
char *argv[]) {
68 ros::init(argc, argv,
"example_integration");
81 joy_sub, menu_sub, 10);
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void onSynchronized(const sensor_msgs::JoyConstPtr &joy, const radial_menu_msgs::StateConstPtr &state)
int main(int argc, char *argv[])
Connection registerCallback(C &callback)
radial_menu_model::Model model
std::string resolveName(const std::string &name, bool remap=true) const
#define ROS_INFO_STREAM(args)
#define ROS_ERROR_STREAM(args)