UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Revision:
7:950b3c3b5a2b
Parent:
6:2ffa254e8f6e
Child:
8:478f75c6109c
--- a/main.cpp	Tue Mar 06 21:44:07 2018 +0000
+++ b/main.cpp	Wed Mar 14 19:33:08 2018 +0000
@@ -10,7 +10,7 @@
 #include "mbed.h"
 #include <ros.h>
 #include <std_msgs/Empty.h>
-#include <std_msgs/Float32MultiArray.h>
+#include <std_msgs/Int32MultiArray.h>
 #include <BNO055.h>
 #include <initializations.h>
 #include <definitions.h>
@@ -27,9 +27,8 @@
 Timer               rosMode_Delay;
 DynamixelClass      gimbal(57600, D7, D8, D2);
 
-
 ros::NodeHandle     nh;
-ros::Subscriber<std_msgs::Float32MultiArray> sub("module_command", &module_commandCB);
+ros::Subscriber<std_msgs::Int32MultiArray> sub("module_command", &module_commandCB);
 
 // Global Variable
 struct          fields control;
@@ -46,6 +45,11 @@
     setupGimbal();                              // Gimbal
     setupLift();                                // Lift
     setupROSNode(nh, sub);                     // ROS Node Handle
+    rosInput.yaw = 1;
+    rosInput.pitch = 1;
+    rosInput.roll = 1;
+    rosInput.height = 1;
+    rosInput.mode = 0;
 
     // Main Loop
     while (1) {