9 #include <walk_and_kick/wak_common.h>
10 #include <rcup_game_controller/GCData.h>
14 namespace walk_and_kick
26 explicit GCRosInterface(ros::NodeHandle& nh) : m_nh(nh), m_enabled(
true) { resetData(); }
30 void resetData() { m_data = rcup_game_controller::GCData(); }
33 void startListening() { stopListening(); m_subscriber = m_nh.subscribe(
"/game_controller/data", 1, &GCRosInterface::handleGameControllerData,
this); }
34 void stopListening() { m_subscriber.shutdown(); }
37 bool getEnabled()
const {
return m_enabled; }
38 void setEnabled(
bool enabled) { m_enabled = enabled; }
41 const rcup_game_controller::GCData& data()
const {
return m_data; }
51 rcup_game_controller::GCData m_data;
54 ros::Subscriber m_subscriber;
55 void handleGameControllerData(
const rcup_game_controller::GCDataConstPtr& msg) {
if(m_enabled) m_data = *msg; }
An interface class to the ROS world for getting game controller messages.
Definition: wak_gc_ros.h:21