Subscribe "cmd_vel"

Dependencies:   ros_lib_kinetic

Committer:
cpbenite
Date:
Fri Nov 02 23:53:38 2018 +0000
Revision:
0:d6f223f1ea8a
Hi Jesus;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
cpbenite 0:d6f223f1ea8a 1 #include "mbed.h"
cpbenite 0:d6f223f1ea8a 2 #include <ros.h>
cpbenite 0:d6f223f1ea8a 3 #include <geometry_msgs/Twist.h>
cpbenite 0:d6f223f1ea8a 4
cpbenite 0:d6f223f1ea8a 5 // Initialize ROS Node & Twist Message
cpbenite 0:d6f223f1ea8a 6 ros::NodeHandle nh;
cpbenite 0:d6f223f1ea8a 7 geometry_msgs::Twist commandRead;
cpbenite 0:d6f223f1ea8a 8
cpbenite 0:d6f223f1ea8a 9 ros::Publisher chatter("chatter", &commandRead);
cpbenite 0:d6f223f1ea8a 10
cpbenite 0:d6f223f1ea8a 11 // Initialize Subscribe Callback Functions
cpbenite 0:d6f223f1ea8a 12 void handlerFunction(const geometry_msgs::Twist& command){
cpbenite 0:d6f223f1ea8a 13 commandRead = command;
cpbenite 0:d6f223f1ea8a 14 }
cpbenite 0:d6f223f1ea8a 15 ros::Subscriber<geometry_msgs::Twist> sub("cmd_vel", &handlerFunction);
cpbenite 0:d6f223f1ea8a 16
cpbenite 0:d6f223f1ea8a 17 int main() {
cpbenite 0:d6f223f1ea8a 18 // Initalize Node and Subscribe to Topic "cmd_vel"
cpbenite 0:d6f223f1ea8a 19 nh.initNode();
cpbenite 0:d6f223f1ea8a 20 nh.subscribe(sub);
cpbenite 0:d6f223f1ea8a 21 //nh.advertise(chatter);
cpbenite 0:d6f223f1ea8a 22
cpbenite 0:d6f223f1ea8a 23 //commandRead.linear.x = 6.9;
cpbenite 0:d6f223f1ea8a 24
cpbenite 0:d6f223f1ea8a 25 while (1) {
cpbenite 0:d6f223f1ea8a 26 // Jesus change line here
cpbenite 0:d6f223f1ea8a 27 // commandRead = actual velocity numbers
cpbenite 0:d6f223f1ea8a 28 // commandRead.linear.x = forward velocity
cpbenite 0:d6f223f1ea8a 29 // commandRead.angular.z = turning velocity
cpbenite 0:d6f223f1ea8a 30 chatter.publish(&commandRead);
cpbenite 0:d6f223f1ea8a 31 nh.spinOnce();
cpbenite 0:d6f223f1ea8a 32 wait_ms(10);
cpbenite 0:d6f223f1ea8a 33 }
cpbenite 0:d6f223f1ea8a 34 }
cpbenite 0:d6f223f1ea8a 35