diff --git a/ROS/gesture_based_control/launch/gesture_control.launch b/ROS/gesture_based_control/launch/gesture_control.launch
index 7bfe4d6..316aa9a 100644
--- a/ROS/gesture_based_control/launch/gesture_control.launch
+++ b/ROS/gesture_based_control/launch/gesture_control.launch
@@ -1,6 +1,10 @@
-
+
+
+
-
+
+
+
diff --git a/ROS/gesture_based_control/src/controller.cpp b/ROS/gesture_based_control/src/controller.cpp
index d0639d8..6223ccb 100644
--- a/ROS/gesture_based_control/src/controller.cpp
+++ b/ROS/gesture_based_control/src/controller.cpp
@@ -1,17 +1,38 @@
#include
#include
+#include
-void callback(const std_msgs::String& msg) {
- //ROS_INFO("coucou");
+void callback(const std_msgs::String& msg, geometry_msgs::Twist& cmd) {
+ if (msg.data == "forward") {
+ cmd.linear.x = 1.0;
+ cmd.angular.z = 0.0;
+ } else if (msg.data == "stop") {
+ cmd = geometry_msgs::Twist();
+ } else if (msg.data == "left") {
+ cmd.angular.z = 1.0;
+ cmd.linear.x = 0.0;
+ } else if (msg.data == "right") {
+ cmd.angular.z = -1.0;
+ cmd.linear.x = 0.0;
+ }
}
int main(int argc, char** argv) {
ros::init(argc, argv, "controller");
- /*
ros::NodeHandle n;
- ros::Subscriber sub = n.subscribe("/order", 0, callback);
- ros::spin();
- */
+ ros::Publisher pub = n.advertise("/cmd_vel", 0);
+
+ geometry_msgs::Twist cmd;
+ ros::Rate rate(10);
+
+ boost::function cb = boost::bind(callback, _1, boost::ref(cmd));
+ ros::Subscriber sub = n.subscribe("/order", 0, cb);
+
+ while(ros::ok()) {
+ pub.publish(cmd);
+ ros::spinOnce();
+ rate.sleep();
+ }
return 0;
}