5 #ifndef HAND_SHAKING_DEMO_H
6 #define HAND_SHAKING_DEMO_H
9 #include <nimbro_op_interface/Button.h>
10 #include <config_server/parameter.h>
11 #include <robotcontrol/State.h>
12 #include <ros/service.h>
16 namespace hand_shaking_demo
30 inline bool enabled()
const {
return m_handShakingDemoEnabled(); }
34 ros::ServiceClient m_srv_playMotion;
37 ros::Subscriber m_sub_button;
40 void playMotion(
const std::string& motionName);
43 void handleButton(
const nimbro_op_interface::ButtonConstPtr& msg);
47 ros::Subscriber m_sub_robotState;
49 std::string m_robotStateName;
50 bool m_robotIsStanding;
51 bool m_robotIsShaking;
54 config_server::Parameter<bool> m_handShakingDemoEnabled;
55 void handleDemoEnabled();
58 ros::Time m_curStepTime;
boost::shared_ptr< State const > StateConstPtr
Used to represent a Boost shared pointer to a constant State object.
Definition: state_controller.h:413