Rogelio Vazquez / Mbed 2 deprecated __launcher_communication

Dependencies:   ros_lib_indigo mbed

Committer:
roger_wee
Date:
Tue Apr 23 18:37:20 2019 +0000
Revision:
0:583c5af1418c
Senior design communication script

Who changed what in which revision?

UserRevisionLine numberNew contents of line
roger_wee 0:583c5af1418c 1 #include "mbed.h"
roger_wee 0:583c5af1418c 2 #include <ros.h>
roger_wee 0:583c5af1418c 3 #include <std_msgs/Int16.h>
roger_wee 0:583c5af1418c 4
roger_wee 0:583c5af1418c 5 //--------- GLOBAL VARIABLES LOCAL TO STM32 MAIN -----------
roger_wee 0:583c5af1418c 6 DigitalOut my_led(LED1);
roger_wee 0:583c5af1418c 7
roger_wee 0:583c5af1418c 8 int data_recieved = 0;
roger_wee 0:583c5af1418c 9
roger_wee 0:583c5af1418c 10 //-------- END GLOBAL VARIABLES DECLARATION ---------------
roger_wee 0:583c5af1418c 11
roger_wee 0:583c5af1418c 12
roger_wee 0:583c5af1418c 13 //--------- ROS NODE CONFIGURATION -------------------------
roger_wee 0:583c5af1418c 14 ros::NodeHandle nh;
roger_wee 0:583c5af1418c 15
roger_wee 0:583c5af1418c 16 // Ros message data containers
roger_wee 0:583c5af1418c 17 std_msgs::Int16 recieve_msg;
roger_wee 0:583c5af1418c 18 std_msgs::Int16 transmit_msg;
roger_wee 0:583c5af1418c 19
roger_wee 0:583c5af1418c 20 // Set up Publishers
roger_wee 0:583c5af1418c 21 ros::Publisher acknowledge_publisher("acknowledge", &transmit_msg);
roger_wee 0:583c5af1418c 22
roger_wee 0:583c5af1418c 23 // Set up Subscribers
roger_wee 0:583c5af1418c 24 void reciever_callback( const std_msgs::Int16& msg)
roger_wee 0:583c5af1418c 25 {
roger_wee 0:583c5af1418c 26 // Assign msg.data to local variables
roger_wee 0:583c5af1418c 27 data_recieved = msg.data;
roger_wee 0:583c5af1418c 28 }
roger_wee 0:583c5af1418c 29
roger_wee 0:583c5af1418c 30 ros::Subscriber<std_msgs::Int16> reciever_subscriber("test", reciever_callback);
roger_wee 0:583c5af1418c 31
roger_wee 0:583c5af1418c 32
roger_wee 0:583c5af1418c 33 //---------- END CONFIGURATION ----------------------------
roger_wee 0:583c5af1418c 34
roger_wee 0:583c5af1418c 35 int main() {
roger_wee 0:583c5af1418c 36
roger_wee 0:583c5af1418c 37 // Initialize Node and publisher/subscriber
roger_wee 0:583c5af1418c 38 nh.initNode();
roger_wee 0:583c5af1418c 39 nh.advertise(acknowledge_publisher);
roger_wee 0:583c5af1418c 40 nh.subscribe(reciever_subscriber);
roger_wee 0:583c5af1418c 41
roger_wee 0:583c5af1418c 42 while(1) {
roger_wee 0:583c5af1418c 43
roger_wee 0:583c5af1418c 44 // Use local variables for computations here
roger_wee 0:583c5af1418c 45
roger_wee 0:583c5af1418c 46
roger_wee 0:583c5af1418c 47 // Publish any data necessary to be fed back to pc
roger_wee 0:583c5af1418c 48 transmit_msg.data = data_recieved;
roger_wee 0:583c5af1418c 49 acknowledge_publisher.publish(&transmit_msg);
roger_wee 0:583c5af1418c 50
roger_wee 0:583c5af1418c 51 // Spin ROS Node -- get data from callbacks
roger_wee 0:583c5af1418c 52 nh.spinOnce();
roger_wee 0:583c5af1418c 53 wait_ms(5);
roger_wee 0:583c5af1418c 54 }
roger_wee 0:583c5af1418c 55 }